| /// autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE |
| /// \author Rosen Diankov |
| /// |
| /// Licensed under the Apache License, Version 2.0 (the "License"); |
| /// you may not use this file except in compliance with the License. |
| /// You may obtain a copy of the License at |
| /// http://www.apache.org/licenses/LICENSE-2.0 |
| /// |
| /// Unless required by applicable law or agreed to in writing, software |
| /// distributed under the License is distributed on an "AS IS" BASIS, |
| /// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| /// See the License for the specific language governing permissions and |
| /// limitations under the License. |
| /// |
| /// ikfast version 0x1000004a generated on 2018-01-21 23:37:30.503597 |
| /// Generated using solver transform6d |
| /// To compile with gcc: |
| /// gcc -lstdc++ ik.cpp |
| /// To compile without any main function as a shared object (might need -llapack): |
| /// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp |
| #define IKFAST_HAS_LIBRARY |
| #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h |
| using namespace ikfast; |
| |
| // check if the included ikfast version matches what this file was compiled with |
| #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x] |
| IKFAST_COMPILE_ASSERT(IKFAST_VERSION==0x1000004a); |
| |
| #include <cmath> |
| #include <vector> |
| #include <limits> |
| #include <algorithm> |
| #include <complex> |
| |
| #ifndef IKFAST_ASSERT |
| #include <stdexcept> |
| #include <sstream> |
| #include <iostream> |
| |
| #ifdef _MSC_VER |
| #ifndef __PRETTY_FUNCTION__ |
| #define __PRETTY_FUNCTION__ __FUNCDNAME__ |
| #endif |
| #endif |
| |
| #ifndef __PRETTY_FUNCTION__ |
| #define __PRETTY_FUNCTION__ __func__ |
| #endif |
| |
| #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()); } } |
| |
| #endif |
| |
| #if defined(_MSC_VER) |
| #define IKFAST_ALIGNED16(x) __declspec(align(16)) x |
| #else |
| #define IKFAST_ALIGNED16(x) x __attribute((aligned(16))) |
| #endif |
| |
| #define IK2PI ((IkReal)6.28318530717959) |
| #define IKPI ((IkReal)3.14159265358979) |
| #define IKPI_2 ((IkReal)1.57079632679490) |
| |
| #ifdef _MSC_VER |
| #ifndef isnan |
| #define isnan _isnan |
| #endif |
| #ifndef isinf |
| #define isinf _isinf |
| #endif |
| //#ifndef isfinite |
| //#define isfinite _isfinite |
| //#endif |
| #endif // _MSC_VER |
| |
| // lapack routines |
| extern "C" { |
| void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info); |
| void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info); |
| void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info); |
| void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info); |
| 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); |
| 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); |
| } |
| |
| using namespace std; // necessary to get std math routines |
| |
| #ifdef IKFAST_NAMESPACE |
| namespace IKFAST_NAMESPACE { |
| #endif |
| |
| inline float IKabs(float f) { return fabsf(f); } |
| inline double IKabs(double f) { return fabs(f); } |
| |
| inline float IKsqr(float f) { return f*f; } |
| inline double IKsqr(double f) { return f*f; } |
| |
| inline float IKlog(float f) { return logf(f); } |
| inline double IKlog(double f) { return log(f); } |
| |
| // allows asin and acos to exceed 1. has to be smaller than thresholds used for branch conds and evaluation |
| #ifndef IKFAST_SINCOS_THRESH |
| #define IKFAST_SINCOS_THRESH ((IkReal)1e-7) |
| #endif |
| |
| // used to check input to atan2 for degenerate cases. has to be smaller than thresholds used for branch conds and evaluation |
| #ifndef IKFAST_ATAN2_MAGTHRESH |
| #define IKFAST_ATAN2_MAGTHRESH ((IkReal)1e-7) |
| #endif |
| |
| // minimum distance of separate solutions |
| #ifndef IKFAST_SOLUTION_THRESH |
| #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6) |
| #endif |
| |
| // there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate |
| #ifndef IKFAST_EVALCOND_THRESH |
| #define IKFAST_EVALCOND_THRESH ((IkReal)0.00001) |
| #endif |
| |
| |
| inline float IKasin(float f) |
| { |
| IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver |
| if( f <= -1 ) return float(-IKPI_2); |
| else if( f >= 1 ) return float(IKPI_2); |
| return asinf(f); |
| } |
| inline double IKasin(double f) |
| { |
| IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver |
| if( f <= -1 ) return -IKPI_2; |
| else if( f >= 1 ) return IKPI_2; |
| return asin(f); |
| } |
| |
| // return positive value in [0,y) |
| inline float IKfmod(float x, float y) |
| { |
| while(x < 0) { |
| x += y; |
| } |
| return fmodf(x,y); |
| } |
| |
| // return positive value in [0,y) |
| inline double IKfmod(double x, double y) |
| { |
| while(x < 0) { |
| x += y; |
| } |
| return fmod(x,y); |
| } |
| |
| inline float IKacos(float f) |
| { |
| IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver |
| if( f <= -1 ) return float(IKPI); |
| else if( f >= 1 ) return float(0); |
| return acosf(f); |
| } |
| inline double IKacos(double f) |
| { |
| IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver |
| if( f <= -1 ) return IKPI; |
| else if( f >= 1 ) return 0; |
| return acos(f); |
| } |
| inline float IKsin(float f) { return sinf(f); } |
| inline double IKsin(double f) { return sin(f); } |
| inline float IKcos(float f) { return cosf(f); } |
| inline double IKcos(double f) { return cos(f); } |
| inline float IKtan(float f) { return tanf(f); } |
| inline double IKtan(double f) { return tan(f); } |
| inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); } |
| inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); } |
| inline float IKatan2Simple(float fy, float fx) { |
| return atan2f(fy,fx); |
| } |
| inline float IKatan2(float fy, float fx) { |
| if( isnan(fy) ) { |
| IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned |
| return float(IKPI_2); |
| } |
| else if( isnan(fx) ) { |
| return 0; |
| } |
| return atan2f(fy,fx); |
| } |
| inline double IKatan2Simple(double fy, double fx) { |
| return atan2(fy,fx); |
| } |
| inline double IKatan2(double fy, double fx) { |
| if( isnan(fy) ) { |
| IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned |
| return IKPI_2; |
| } |
| else if( isnan(fx) ) { |
| return 0; |
| } |
| return atan2(fy,fx); |
| } |
| |
| template <typename T> |
| struct CheckValue |
| { |
| T value; |
| bool valid; |
| }; |
| |
| template <typename T> |
| inline CheckValue<T> IKatan2WithCheck(T fy, T fx, T epsilon) |
| { |
| CheckValue<T> ret; |
| ret.valid = false; |
| ret.value = 0; |
| if( !isnan(fy) && !isnan(fx) ) { |
| if( IKabs(fy) >= IKFAST_ATAN2_MAGTHRESH || IKabs(fx) > IKFAST_ATAN2_MAGTHRESH ) { |
| ret.value = IKatan2Simple(fy,fx); |
| ret.valid = true; |
| } |
| } |
| return ret; |
| } |
| |
| inline float IKsign(float f) { |
| if( f > 0 ) { |
| return float(1); |
| } |
| else if( f < 0 ) { |
| return float(-1); |
| } |
| return 0; |
| } |
| |
| inline double IKsign(double f) { |
| if( f > 0 ) { |
| return 1.0; |
| } |
| else if( f < 0 ) { |
| return -1.0; |
| } |
| return 0; |
| } |
| |
| template <typename T> |
| inline CheckValue<T> IKPowWithIntegerCheck(T f, int n) |
| { |
| CheckValue<T> ret; |
| ret.valid = true; |
| if( n == 0 ) { |
| ret.value = 1.0; |
| return ret; |
| } |
| else if( n == 1 ) |
| { |
| ret.value = f; |
| return ret; |
| } |
| else if( n < 0 ) |
| { |
| if( f == 0 ) |
| { |
| ret.valid = false; |
| ret.value = (T)1.0e30; |
| return ret; |
| } |
| if( n == -1 ) { |
| ret.value = T(1.0)/f; |
| return ret; |
| } |
| } |
| |
| int num = n > 0 ? n : -n; |
| if( num == 2 ) { |
| ret.value = f*f; |
| } |
| else if( num == 3 ) { |
| ret.value = f*f*f; |
| } |
| else { |
| ret.value = 1.0; |
| while(num>0) { |
| if( num & 1 ) { |
| ret.value *= f; |
| } |
| num >>= 1; |
| f *= f; |
| } |
| } |
| |
| if( n < 0 ) { |
| ret.value = T(1.0)/ret.value; |
| } |
| return ret; |
| } |
| |
| /// solves the forward kinematics equations. |
| /// \param pfree is an array specifying the free joints of the chain. |
| IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) { |
| 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; |
| x0=IKcos(j[0]); |
| x1=IKcos(j[2]); |
| x2=IKsin(j[0]); |
| x3=IKsin(j[1]); |
| x4=IKsin(j[2]); |
| x5=IKcos(j[3]); |
| x6=IKcos(j[1]); |
| x7=IKsin(j[3]); |
| x8=IKcos(j[5]); |
| x9=IKsin(j[5]); |
| x10=IKcos(j[4]); |
| x11=IKsin(j[4]); |
| x12=((0.02075)*x3); |
| x13=((0.03)*x5); |
| x14=((1.0)*x2); |
| x15=((1.0)*x6); |
| x16=((0.296)*x5); |
| x17=((0.03)*x11); |
| x18=((0.03)*x7); |
| x19=((1.0)*x3); |
| x20=((0.02075)*x5); |
| x21=((1.0)*x7); |
| x22=((0.03)*x10); |
| x23=(x0*x4); |
| x24=(x0*x6); |
| x25=(x2*x4); |
| x26=(x6*x7); |
| x27=(x2*x6); |
| x28=(x0*x1); |
| x29=(x1*x3); |
| x30=(x1*x5*x6); |
| x31=(x10*x4*x6); |
| x32=(x19*x28); |
| x33=(x0*x15*x5); |
| x34=(x14*x5*x6); |
| x35=(x14*x3*x4); |
| x36=((((-1.0)*x32))+x25); |
| x37=((((-1.0)*x35))+x28); |
| x38=((((-1.0)*x19*x7))+x30); |
| x39=((((-1.0)*x14*x4))+x32); |
| x40=(((x19*x23))+((x1*x14))); |
| x41=((-1.0)*x40); |
| x42=(((x14*x29))+(((1.0)*x23))); |
| x43=((-1.0)*x42); |
| x44=(((x1*x15*x7))+((x19*x5))); |
| x45=(x10*x37); |
| x46=(x11*x38); |
| x47=(x36*x5); |
| x48=(x39*x7); |
| x49=(x42*x7); |
| x50=(x10*x41); |
| x51=(x47+(((-1.0)*x0*x15*x7))); |
| x52=(x31+x46); |
| x53=((((-1.0)*x14*x26))+((x43*x5))); |
| x54=(((x11*x51))+x50); |
| x55=(((x11*x53))+x45); |
| eerot[0]=(((x8*((x33+(((-1.0)*x21*x39))))))+((x54*x9))); |
| eerot[1]=(((x54*x8))+((x9*(((((-1.0)*x33))+x48))))); |
| eerot[2]=(((x11*x40))+((x10*x51))); |
| 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))))))); |
| eerot[3]=(((x55*x9))+((x8*((x34+(((-1.0)*x21*x42))))))); |
| eerot[4]=(((x9*(((((-1.0)*x34))+x49))))+((x55*x8))); |
| eerot[5]=(((x11*(((((-1.0)*x28))+x35))))+((x10*x53))); |
| 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))); |
| eerot[6]=(((x44*x8))+((x52*x9))); |
| eerot[7]=((((-1.0)*x44*x9))+((x52*x8))); |
| eerot[8]=(((x10*x38))+(((-1.0)*x11*x15*x4))); |
| IkReal x56=(x1*x6); |
| 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))))))); |
| } |
| |
| IKFAST_API int GetNumFreeParameters() { return 0; } |
| IKFAST_API int* GetFreeParameters() { return NULL; } |
| IKFAST_API int GetNumJoints() { return 6; } |
| |
| IKFAST_API int GetIkRealSize() { return sizeof(IkReal); } |
| |
| IKFAST_API int GetIkType() { return 0x67000001; } |
| |
| class IKSolver { |
| public: |
| 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; |
| unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5; |
| |
| IkReal j100, cj100, sj100; |
| unsigned char _ij100[2], _nj100; |
| bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) { |
| 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; |
| for(int dummyiter = 0; dummyiter < 1; ++dummyiter) { |
| solutions.Clear(); |
| r00 = eerot[0*3+0]; |
| r01 = eerot[0*3+1]; |
| r02 = eerot[0*3+2]; |
| r10 = eerot[1*3+0]; |
| r11 = eerot[1*3+1]; |
| r12 = eerot[1*3+2]; |
| r20 = eerot[2*3+0]; |
| r21 = eerot[2*3+1]; |
| r22 = eerot[2*3+2]; |
| px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; |
| |
| new_r00=r01; |
| new_r01=((-1.0)*r00); |
| new_r02=r02; |
| new_px=(px+(((-0.03)*r00))); |
| new_r10=r11; |
| new_r11=((-1.0)*r10); |
| new_r12=r12; |
| new_py=(py+(((-0.03)*r10))); |
| new_r20=r21; |
| new_r21=((-1.0)*r20); |
| new_r22=r22; |
| new_pz=((-0.178)+(((-0.03)*r20))+pz); |
| 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; |
| IkReal x57=((1.0)*px); |
| IkReal x58=((1.0)*pz); |
| IkReal x59=((1.0)*py); |
| pp=((px*px)+(py*py)+(pz*pz)); |
| npx=(((px*r00))+((py*r10))+((pz*r20))); |
| npy=(((px*r01))+((py*r11))+((pz*r21))); |
| npz=(((px*r02))+((py*r12))+((pz*r22))); |
| rxp0_0=((((-1.0)*r20*x59))+((pz*r10))); |
| rxp0_1=(((px*r20))+(((-1.0)*r00*x58))); |
| rxp0_2=((((-1.0)*r10*x57))+((py*r00))); |
| rxp1_0=((((-1.0)*r21*x59))+((pz*r11))); |
| rxp1_1=(((px*r21))+(((-1.0)*r01*x58))); |
| rxp1_2=((((-1.0)*r11*x57))+((py*r01))); |
| rxp2_0=(((pz*r12))+(((-1.0)*r22*x59))); |
| rxp2_1=(((px*r22))+(((-1.0)*r02*x58))); |
| rxp2_2=((((-1.0)*r12*x57))+((py*r02))); |
| { |
| IkReal j4eval[1]; |
| IkReal x60=pp*pp; |
| IkReal x61=npz*npz; |
| IkReal x62=((0.030003082397184)*npz); |
| IkReal x63=((0.114909184)*npz*pp); |
| 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)))))))); |
| if( IKabs(j4eval[0]) < 0.0000000100000000 ) |
| { |
| continue; // no branches [j3, j4, j5] |
| |
| } else |
| { |
| IkReal op[8+1], zeror[8]; |
| int numroots; |
| IkReal x64=npz*npz; |
| IkReal x65=pp*pp; |
| IkReal x66=((0.030003082397184)*npz); |
| IkReal x67=((0.114909184)*npz*pp); |
| IkReal x68=(x66+(((-1.0)*x67))); |
| IkReal x69=((-0.97516709888)*x64); |
| IkReal x70=(x67+(((-1.0)*x66))); |
| IkReal x71=((-0.00520874343240181)+(((-0.242599591936)*x64))+(((0.361482920448)*pp))+(((-0.692224)*x65))); |
| op[0]=x71; |
| op[1]=x68; |
| op[2]=x69; |
| op[3]=x68; |
| op[4]=((0.0104174868648036)+(((-1.465135013888)*x64))+(((1.384448)*x65))+(((-0.722965840896)*pp))); |
| op[5]=x70; |
| op[6]=x69; |
| op[7]=x70; |
| op[8]=x71; |
| polyroots8(op,zeror,numroots); |
| IkReal j4array[8], cj4array[8], sj4array[8], tempj4array[1]; |
| int numsolutions = 0; |
| for(int ij4 = 0; ij4 < numroots; ++ij4) |
| { |
| IkReal htj4 = zeror[ij4]; |
| tempj4array[0]=((2.0)*(atan(htj4))); |
| for(int kj4 = 0; kj4 < 1; ++kj4) |
| { |
| j4array[numsolutions] = tempj4array[kj4]; |
| if( j4array[numsolutions] > IKPI ) |
| { |
| j4array[numsolutions]-=IK2PI; |
| } |
| else if( j4array[numsolutions] < -IKPI ) |
| { |
| j4array[numsolutions]+=IK2PI; |
| } |
| sj4array[numsolutions] = IKsin(j4array[numsolutions]); |
| cj4array[numsolutions] = IKcos(j4array[numsolutions]); |
| numsolutions++; |
| } |
| } |
| bool j4valid[8]={true,true,true,true,true,true,true,true}; |
| _nj4 = 8; |
| for(int ij4 = 0; ij4 < numsolutions; ++ij4) |
| { |
| if( !j4valid[ij4] ) |
| { |
| continue; |
| } |
| j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4]; |
| htj4 = IKtan(j4/2); |
| |
| _ij4[0] = ij4; _ij4[1] = -1; |
| for(int iij4 = ij4+1; iij4 < numsolutions; ++iij4) |
| { |
| if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j4valid[iij4]=false; _ij4[1] = iij4; break; |
| } |
| } |
| { |
| IkReal j3eval[1]; |
| j3eval[0]=cj4; |
| if( IKabs(j3eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j5eval[2]; |
| IkReal x72=cj4*cj4; |
| j5eval[0]=(((x72*(npx*npx)))+((x72*(npy*npy)))); |
| j5eval[1]=((IKabs((cj4*npy)))+(IKabs((cj4*npx)))); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[2]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); |
| evalcond[1]=npz; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j3array[2], cj3array[2], sj3array[2]; |
| bool j3valid[2]={false}; |
| _nj3 = 2; |
| if( (((-1.05762474974545)+(((4.05061037938089)*pp)))) < -1-IKFAST_SINCOS_THRESH || (((-1.05762474974545)+(((4.05061037938089)*pp)))) > 1+IKFAST_SINCOS_THRESH ) |
| continue; |
| IkReal x73=IKasin(((-1.05762474974545)+(((4.05061037938089)*pp)))); |
| j3array[0]=((1.50080946872133)+(((-1.0)*x73))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| j3array[1]=((4.64240212231113)+x73); |
| sj3array[1]=IKsin(j3array[1]); |
| cj3array[1]=IKcos(j3array[1]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| if( j3array[1] > IKPI ) |
| { |
| j3array[1]-=IK2PI; |
| } |
| else if( j3array[1] < -IKPI ) |
| { j3array[1]+=IK2PI; |
| } |
| j3valid[1] = true; |
| for(int ij3 = 0; ij3 < 2; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 2; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| |
| { |
| IkReal j5eval[3]; |
| sj4=1.0; |
| cj4=0; |
| j4=1.5707963267949; |
| IkReal x74=((0.416)*cj3); |
| IkReal x75=((0.416)*sj3); |
| IkReal x76=((npx*npx)+(npy*npy)); |
| j5eval[0]=x76; |
| 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)))))); |
| j5eval[2]=IKsign(x76); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j5eval[3]; |
| sj4=1.0; |
| cj4=0; |
| j4=1.5707963267949; |
| IkReal x77=npx*npx; |
| IkReal x78=npy*npy; |
| IkReal x79=(cj3*npy); |
| IkReal x80=(cj3*npx); |
| IkReal x81=((2000.0)*pp); |
| j5eval[0]=(x77+x78); |
| j5eval[1]=IKsign(((((83.0)*x77))+(((83.0)*x78)))); |
| 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)))))); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j5] |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x82=(cj3*npy); |
| IkReal x83=(cj3*npx); |
| IkReal x84=((2000.0)*pp); |
| 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); |
| if(!x85.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x86=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| if(!x86.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x85.value)+(((1.5707963267949)*(x86.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[3]; |
| IkReal x87=IKcos(j5); |
| IkReal x88=IKsin(j5); |
| IkReal x89=((1.0)*x87); |
| IkReal x90=(npy*x88); |
| evalcond[0]=((0.02075)+(((-0.416)*sj3))+x90+(((-1.0)*npx*x89))); |
| evalcond[1]=((-0.296)+(((-1.0)*npx*x88))+(((-0.416)*cj3))+(((-1.0)*npy*x89))); |
| evalcond[2]=((-0.2602414375)+(((-0.0415)*npx*x87))+(((-0.246272)*cj3))+pp+(((0.0415)*x90))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x1857=((0.416)*cj3); |
| IkReal x1858=((0.416)*sj3); |
| 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); |
| if(!x1859.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1860=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| if(!x1860.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x1859.value)+(((1.5707963267949)*(x1860.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1861=IKcos(j5); |
| IkReal x1862=IKsin(j5); |
| IkReal x1863=((1.0)*x1861); |
| IkReal x1864=(npy*x1862); |
| evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1863))+x1864); |
| evalcond[1]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x1862))+(((-1.0)*npy*x1863))); |
| evalcond[2]=((-0.2602414375)+(((-0.246272)*cj3))+pp+(((0.0415)*x1864))+(((-0.0415)*npx*x1861))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j3array[2], cj3array[2], sj3array[2]; |
| bool j3valid[2]={false}; |
| _nj3 = 2; |
| if( (((-1.05762474974545)+(((4.05061037938089)*pp)))) < -1-IKFAST_SINCOS_THRESH || (((-1.05762474974545)+(((4.05061037938089)*pp)))) > 1+IKFAST_SINCOS_THRESH ) |
| continue; |
| IkReal x1865=IKasin(((-1.05762474974545)+(((4.05061037938089)*pp)))); |
| j3array[0]=((1.64078318486846)+(((-1.0)*x1865))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| j3array[1]=((4.78237583845825)+x1865); |
| sj3array[1]=IKsin(j3array[1]); |
| cj3array[1]=IKcos(j3array[1]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| if( j3array[1] > IKPI ) |
| { |
| j3array[1]-=IK2PI; |
| } |
| else if( j3array[1] < -IKPI ) |
| { j3array[1]+=IK2PI; |
| } |
| j3valid[1] = true; |
| for(int ij3 = 0; ij3 < 2; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 2; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| |
| { |
| IkReal j5eval[3]; |
| sj4=-1.0; |
| cj4=0; |
| j4=-1.5707963267949; |
| IkReal x1866=((0.416)*cj3); |
| IkReal x1867=((0.416)*sj3); |
| IkReal x1868=((npx*npx)+(npy*npy)); |
| j5eval[0]=x1868; |
| j5eval[1]=IKsign(x1868); |
| 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)))))); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j5eval[3]; |
| sj4=-1.0; |
| cj4=0; |
| j4=-1.5707963267949; |
| IkReal x1869=npx*npx; |
| IkReal x1870=npy*npy; |
| IkReal x1871=(cj3*npy); |
| IkReal x1872=(cj3*npx); |
| IkReal x1873=((2000.0)*pp); |
| j5eval[0]=(x1869+x1870); |
| j5eval[1]=IKsign(((((83.0)*x1869))+(((83.0)*x1870)))); |
| 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)))))); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j5] |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x1874=(cj3*npy); |
| IkReal x1875=(cj3*npx); |
| IkReal x1876=((2000.0)*pp); |
| 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); |
| if(!x1877.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1878=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| if(!x1878.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x1877.value)+(((1.5707963267949)*(x1878.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1879=IKcos(j5); |
| IkReal x1880=IKsin(j5); |
| IkReal x1881=((1.0)*x1879); |
| IkReal x1882=(npy*x1880); |
| evalcond[0]=((0.02075)+(((-1.0)*npx*x1881))+x1882+(((0.416)*sj3))); |
| evalcond[1]=((-0.296)+(((-1.0)*npx*x1880))+(((-0.416)*cj3))+(((-1.0)*npy*x1881))); |
| evalcond[2]=((-0.2602414375)+(((0.0415)*x1882))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1879))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x1883=((0.416)*cj3); |
| IkReal x1884=((0.416)*sj3); |
| 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); |
| if(!x1885.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1886=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| if(!x1886.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x1885.value)+(((1.5707963267949)*(x1886.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1887=IKcos(j5); |
| IkReal x1888=IKsin(j5); |
| IkReal x1889=((1.0)*x1887); |
| IkReal x1890=(npy*x1888); |
| evalcond[0]=((0.02075)+(((-1.0)*npx*x1889))+x1890+(((0.416)*sj3))); |
| evalcond[1]=((-0.296)+(((-1.0)*npx*x1888))+(((-0.416)*cj3))+(((-1.0)*npy*x1889))); |
| evalcond[2]=((-0.2602414375)+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1887))+(((0.0415)*x1890))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j3, j5] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j5array[2], cj5array[2], sj5array[2]; |
| bool j5valid[2]={false}; |
| _nj5 = 2; |
| IkReal x1891=cj4*cj4; |
| CheckValue<IkReal> x1894 = IKatan2WithCheck(IkReal(((-1.0)*cj4*npx)),IkReal((cj4*npy)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1894.valid){ |
| continue; |
| } |
| IkReal x1892=((1.0)*(x1894.value)); |
| if(((((x1891*(npy*npy)))+((x1891*(npx*npx))))) < -0.00001) |
| continue; |
| CheckValue<IkReal> x1895=IKPowWithIntegerCheck(IKabs(IKsqrt((((x1891*(npy*npy)))+((x1891*(npx*npx)))))),-1); |
| if(!x1895.valid){ |
| continue; |
| } |
| if( (((x1895.value)*(((((0.02075)*cj4))+((npz*sj4)))))) < -1-IKFAST_SINCOS_THRESH || (((x1895.value)*(((((0.02075)*cj4))+((npz*sj4)))))) > 1+IKFAST_SINCOS_THRESH ) |
| continue; |
| IkReal x1893=IKasin(((x1895.value)*(((((0.02075)*cj4))+((npz*sj4)))))); |
| j5array[0]=((((-1.0)*x1893))+(((-1.0)*x1892))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| j5array[1]=((3.14159265358979)+x1893+(((-1.0)*x1892))); |
| sj5array[1]=IKsin(j5array[1]); |
| cj5array[1]=IKcos(j5array[1]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| if( j5array[1] > IKPI ) |
| { |
| j5array[1]-=IK2PI; |
| } |
| else if( j5array[1] < -IKPI ) |
| { j5array[1]+=IK2PI; |
| } |
| j5valid[1] = true; |
| for(int ij5 = 0; ij5 < 2; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 2; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| |
| { |
| IkReal j3eval[1]; |
| j3eval[0]=cj4; |
| if( IKabs(j3eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j3eval[1]; |
| j3eval[0]=sj4; |
| if( IKabs(j3eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[2]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j3array[1], cj3array[1], sj3array[1]; |
| bool j3valid[1]={false}; |
| _nj3 = 1; |
| 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 ) |
| continue; |
| j3array[0]=IKatan2(((-2.40384615384615)*npz), ((-1.06022025443412)+(((4.06055093555094)*pp)))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| for(int ij3 = 0; ij3 < 1; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1896=IKcos(j3); |
| evalcond[0]=((-0.2611025625)+(((-0.246272)*x1896))+pp); |
| evalcond[1]=((((-1.0)*npz))+(((-0.416)*(IKsin(j3))))); |
| evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1896))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j3array[1], cj3array[1], sj3array[1]; |
| bool j3valid[1]={false}; |
| _nj3 = 1; |
| 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 ) |
| continue; |
| j3array[0]=IKatan2(((2.40384615384615)*npz), ((-1.06022025443412)+(((4.06055093555094)*pp)))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| for(int ij3 = 0; ij3 < 1; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1897=IKcos(j3); |
| evalcond[0]=((-0.2611025625)+(((-0.246272)*x1897))+pp); |
| evalcond[1]=((((-1.0)*npz))+(((0.416)*(IKsin(j3))))); |
| evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1897))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); |
| evalcond[1]=npz; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j3array[1], cj3array[1], sj3array[1]; |
| bool j3valid[1]={false}; |
| _nj3 = 1; |
| IkReal x1898=(cj5*npx); |
| IkReal x1899=(npy*sj5); |
| 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 ) |
| continue; |
| j3array[0]=IKatan2(((0.0498798076923077)+(((-2.40384615384615)*x1898))+(((2.40384615384615)*x1899))), ((-1.05672361250975)+(((-0.168512863825364)*x1898))+(((4.06055093555094)*pp))+(((0.168512863825364)*x1899)))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| for(int ij3 = 0; ij3 < 1; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| { |
| IkReal evalcond[4]; |
| IkReal x1900=IKsin(j3); |
| IkReal x1901=IKcos(j3); |
| IkReal x1902=(cj5*npx); |
| IkReal x1903=(npy*sj5); |
| IkReal x1904=((0.246272)*x1901); |
| evalcond[0]=((-0.2611025625)+(((0.017264)*x1900))+pp+(((-1.0)*x1904))); |
| evalcond[1]=((0.02075)+(((-0.416)*x1900))+(((-1.0)*x1902))+x1903); |
| evalcond[2]=((-0.296)+(((-0.416)*x1901))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))); |
| evalcond[3]=((-0.2602414375)+(((0.0415)*x1903))+(((-0.0415)*x1902))+pp+(((-1.0)*x1904))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j3array[1], cj3array[1], sj3array[1]; |
| bool j3valid[1]={false}; |
| _nj3 = 1; |
| IkReal x1905=(cj5*npx); |
| IkReal x1906=(npy*sj5); |
| 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 ) |
| continue; |
| j3array[0]=IKatan2(((-0.0498798076923077)+(((2.40384615384615)*x1905))+(((-2.40384615384615)*x1906))), ((-1.05672361250975)+(((4.06055093555094)*pp))+(((-0.168512863825364)*x1905))+(((0.168512863825364)*x1906)))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| for(int ij3 = 0; ij3 < 1; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| { |
| IkReal evalcond[4]; |
| IkReal x1907=IKsin(j3); |
| IkReal x1908=IKcos(j3); |
| IkReal x1909=(cj5*npx); |
| IkReal x1910=(npy*sj5); |
| IkReal x1911=((0.246272)*x1908); |
| evalcond[0]=((-0.2611025625)+(((-0.017264)*x1907))+pp+(((-1.0)*x1911))); |
| evalcond[1]=((0.02075)+(((0.416)*x1907))+(((-1.0)*x1909))+x1910); |
| evalcond[2]=((-0.296)+(((-0.416)*x1908))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))); |
| evalcond[3]=((-0.2602414375)+(((-0.0415)*x1909))+pp+(((0.0415)*x1910))+(((-1.0)*x1911))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j3] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j3array[1], cj3array[1], sj3array[1]; |
| bool j3valid[1]={false}; |
| _nj3 = 1; |
| IkReal x1912=(npx*sj5); |
| IkReal x1913=(cj5*npy); |
| CheckValue<IkReal> x1914=IKPowWithIntegerCheck(sj4,-1); |
| if(!x1914.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| 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)))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| for(int ij3 = 0; ij3 < 1; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1915=IKsin(j3); |
| IkReal x1916=IKcos(j3); |
| IkReal x1917=(cj5*npx); |
| IkReal x1918=((1.0)*npz); |
| IkReal x1919=(npy*sj5); |
| IkReal x1920=((0.246272)*x1916); |
| IkReal x1921=((0.416)*x1915); |
| evalcond[0]=((((-1.0)*cj4*x1921))+(((-1.0)*x1918))); |
| evalcond[1]=((-0.2611025625)+(((-1.0)*x1920))+pp+(((0.017264)*sj4*x1915))); |
| evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1916))); |
| evalcond[3]=((0.02075)+(((-1.0)*sj4*x1921))+(((-1.0)*x1917))+x1919); |
| evalcond[4]=((-0.2602414375)+(((-1.0)*x1920))+pp+(((-0.0415)*x1917))+(((0.0415)*x1919))); |
| evalcond[5]=((((-1.0)*cj4*x1918))+((sj4*x1919))+(((-1.0)*x1921))+(((-1.0)*sj4*x1917))+(((0.02075)*sj4))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j3array[1], cj3array[1], sj3array[1]; |
| bool j3valid[1]={false}; |
| _nj3 = 1; |
| CheckValue<IkReal> x1922=IKPowWithIntegerCheck(cj4,-1); |
| if(!x1922.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j3array[0]=IKatan2(((-2.40384615384615)*npz*(x1922.value)), ((-0.711538461538462)+(((-2.40384615384615)*cj5*npy))+(((-2.40384615384615)*npx*sj5)))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| for(int ij3 = 0; ij3 < 1; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1923=IKsin(j3); |
| IkReal x1924=IKcos(j3); |
| IkReal x1925=(cj5*npx); |
| IkReal x1926=((1.0)*npz); |
| IkReal x1927=(npy*sj5); |
| IkReal x1928=((0.246272)*x1924); |
| IkReal x1929=((0.416)*x1923); |
| evalcond[0]=((((-1.0)*cj4*x1929))+(((-1.0)*x1926))); |
| evalcond[1]=((-0.2611025625)+(((-1.0)*x1928))+pp+(((0.017264)*sj4*x1923))); |
| evalcond[2]=((-0.296)+(((-0.416)*x1924))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))); |
| evalcond[3]=((0.02075)+(((-1.0)*x1925))+(((-1.0)*sj4*x1929))+x1927); |
| evalcond[4]=((-0.2602414375)+(((-0.0415)*x1925))+(((-1.0)*x1928))+pp+(((0.0415)*x1927))); |
| evalcond[5]=(((sj4*x1927))+(((-1.0)*sj4*x1925))+(((-1.0)*cj4*x1926))+(((-1.0)*x1929))+(((0.02075)*sj4))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j3array[1], cj3array[1], sj3array[1]; |
| bool j3valid[1]={false}; |
| _nj3 = 1; |
| CheckValue<IkReal> x1931=IKPowWithIntegerCheck(cj4,-1); |
| if(!x1931.valid){ |
| continue; |
| } |
| IkReal x1930=x1931.value; |
| 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 ) |
| continue; |
| j3array[0]=IKatan2(((-2.40384615384615)*npz*x1930), ((1.62422037422037e-5)*x1930*(((((-10375.0)*npz*sj4))+(((-65275.640625)*cj4))+(((250000.0)*cj4*pp)))))); |
| sj3array[0]=IKsin(j3array[0]); |
| cj3array[0]=IKcos(j3array[0]); |
| if( j3array[0] > IKPI ) |
| { |
| j3array[0]-=IK2PI; |
| } |
| else if( j3array[0] < -IKPI ) |
| { j3array[0]+=IK2PI; |
| } |
| j3valid[0] = true; |
| for(int ij3 = 0; ij3 < 1; ++ij3) |
| { |
| if( !j3valid[ij3] ) |
| { |
| continue; |
| } |
| _ij3[0] = ij3; _ij3[1] = -1; |
| for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| { |
| if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j3valid[iij3]=false; _ij3[1] = iij3; break; |
| } |
| } |
| j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| { |
| IkReal evalcond[2]; |
| IkReal x1932=IKsin(j3); |
| evalcond[0]=((((-0.416)*cj4*x1932))+(((-1.0)*npz))); |
| evalcond[1]=((-0.2611025625)+pp+(((-0.246272)*(IKcos(j3))))+(((0.017264)*sj4*x1932))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| IkReal j5eval[3]; |
| IkReal x1933=((0.416)*cj3); |
| IkReal x1934=((0.416)*sj3*sj4); |
| IkReal x1935=((npx*npx)+(npy*npy)); |
| j5eval[0]=x1935; |
| 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)))))); |
| j5eval[2]=IKsign(x1935); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j5eval[3]; |
| IkReal x1936=(npz*sj4); |
| IkReal x1937=(cj4*npy); |
| IkReal x1938=((0.416)*cj3); |
| IkReal x1939=(cj4*npx); |
| IkReal x1940=(((npx*x1939))+((npy*x1937))); |
| j5eval[0]=x1940; |
| 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)))))); |
| j5eval[2]=IKsign(x1940); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j5eval[3]; |
| IkReal x1941=npx*npx; |
| IkReal x1942=npy*npy; |
| IkReal x1943=(cj3*npy); |
| IkReal x1944=(cj3*npx); |
| IkReal x1945=((2000.0)*pp); |
| j5eval[0]=(x1942+x1941); |
| j5eval[1]=IKsign(((((83.0)*x1942))+(((83.0)*x1941)))); |
| 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)))))); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[2]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); |
| evalcond[1]=npz; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j5eval[3]; |
| sj4=1.0; |
| cj4=0; |
| j4=1.5707963267949; |
| IkReal x1946=((0.416)*cj3); |
| IkReal x1947=((0.416)*sj3); |
| IkReal x1948=((npx*npx)+(npy*npy)); |
| j5eval[0]=x1948; |
| 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)))))); |
| j5eval[2]=IKsign(x1948); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j5eval[3]; |
| sj4=1.0; |
| cj4=0; |
| j4=1.5707963267949; |
| IkReal x1949=npx*npx; |
| IkReal x1950=npy*npy; |
| IkReal x1951=(cj3*npy); |
| IkReal x1952=(cj3*npx); |
| IkReal x1953=((2000.0)*pp); |
| j5eval[0]=(x1949+x1950); |
| j5eval[1]=IKsign(((((83.0)*x1950))+(((83.0)*x1949)))); |
| 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)))))); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j5] |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x1954=(cj3*npy); |
| IkReal x1955=(cj3*npx); |
| IkReal x1956=((2000.0)*pp); |
| CheckValue<IkReal> x1957=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| if(!x1957.valid){ |
| continue; |
| } |
| 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); |
| if(!x1958.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1957.value)))+(x1958.value)); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1959=IKcos(j5); |
| IkReal x1960=IKsin(j5); |
| IkReal x1961=((1.0)*x1959); |
| IkReal x1962=(npy*x1960); |
| evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1961))+x1962); |
| evalcond[1]=((-0.296)+(((-1.0)*npx*x1960))+(((-1.0)*npy*x1961))+(((-0.416)*cj3))); |
| evalcond[2]=((-0.2602414375)+(((0.0415)*x1962))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1959))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x1963=((0.416)*cj3); |
| IkReal x1964=((0.416)*sj3); |
| 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); |
| if(!x1965.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1966=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| if(!x1966.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x1965.value)+(((1.5707963267949)*(x1966.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1967=IKcos(j5); |
| IkReal x1968=IKsin(j5); |
| IkReal x1969=((1.0)*x1967); |
| IkReal x1970=(npy*x1968); |
| evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1969))+x1970); |
| evalcond[1]=((-0.296)+(((-1.0)*npx*x1968))+(((-1.0)*npy*x1969))+(((-0.416)*cj3))); |
| evalcond[2]=((-0.2602414375)+(((0.0415)*x1970))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1967))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j5eval[3]; |
| sj4=-1.0; |
| cj4=0; |
| j4=-1.5707963267949; |
| IkReal x1971=((0.416)*cj3); |
| IkReal x1972=((0.416)*sj3); |
| IkReal x1973=((npx*npx)+(npy*npy)); |
| j5eval[0]=x1973; |
| j5eval[1]=IKsign(x1973); |
| 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)))))); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j5eval[3]; |
| sj4=-1.0; |
| cj4=0; |
| j4=-1.5707963267949; |
| IkReal x1974=npx*npx; |
| IkReal x1975=npy*npy; |
| IkReal x1976=(cj3*npy); |
| IkReal x1977=(cj3*npx); |
| IkReal x1978=((2000.0)*pp); |
| j5eval[0]=(x1975+x1974); |
| j5eval[1]=IKsign(((((83.0)*x1974))+(((83.0)*x1975)))); |
| 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)))))); |
| if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j5] |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x1979=(cj3*npy); |
| IkReal x1980=(cj3*npx); |
| IkReal x1981=((2000.0)*pp); |
| 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); |
| if(!x1982.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1983=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| if(!x1983.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x1982.value)+(((1.5707963267949)*(x1983.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1984=IKcos(j5); |
| IkReal x1985=IKsin(j5); |
| IkReal x1986=((1.0)*x1984); |
| IkReal x1987=(npy*x1985); |
| evalcond[0]=((0.02075)+x1987+(((-1.0)*npx*x1986))+(((0.416)*sj3))); |
| evalcond[1]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npy*x1986))+(((-1.0)*npx*x1985))); |
| evalcond[2]=((-0.2602414375)+(((0.0415)*x1987))+(((-0.0415)*npx*x1984))+(((-0.246272)*cj3))+pp); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x1988=((0.416)*cj3); |
| IkReal x1989=((0.416)*sj3); |
| 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); |
| if(!x1990.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1991=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| if(!x1991.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x1990.value)+(((1.5707963267949)*(x1991.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[3]; |
| IkReal x1992=IKcos(j5); |
| IkReal x1993=IKsin(j5); |
| IkReal x1994=((1.0)*x1992); |
| IkReal x1995=(npy*x1993); |
| evalcond[0]=((0.02075)+(((-1.0)*npx*x1994))+x1995+(((0.416)*sj3))); |
| evalcond[1]=((-0.296)+(((-1.0)*npy*x1994))+(((-1.0)*npx*x1993))+(((-0.416)*cj3))); |
| evalcond[2]=((-0.2602414375)+(((0.0415)*x1995))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1992))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j5] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x1996=(cj3*npy); |
| IkReal x1997=(cj3*npx); |
| IkReal x1998=((2000.0)*pp); |
| 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); |
| if(!x1999.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x2000=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| if(!x2000.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x1999.value)+(((1.5707963267949)*(x2000.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[5]; |
| IkReal x2001=IKsin(j5); |
| IkReal x2002=IKcos(j5); |
| IkReal x2003=((0.416)*sj3); |
| IkReal x2004=(npy*x2001); |
| IkReal x2005=((1.0)*x2002); |
| evalcond[0]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x2001))+(((-1.0)*npy*x2005))); |
| evalcond[1]=((0.02075)+(((-1.0)*npx*x2005))+x2004+(((-1.0)*sj4*x2003))); |
| evalcond[2]=((-0.2602414375)+(((0.0415)*x2004))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x2002))); |
| evalcond[3]=(((cj4*x2004))+(((0.02075)*cj4))+((npz*sj4))+(((-1.0)*cj4*npx*x2005))); |
| evalcond[4]=((((-1.0)*cj4*npz))+(((-1.0)*x2003))+(((-1.0)*npx*sj4*x2005))+((sj4*x2004))+(((0.02075)*sj4))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x2006=(npz*sj4); |
| IkReal x2007=(cj4*npy); |
| IkReal x2008=((0.416)*cj3); |
| IkReal x2009=(cj4*npx); |
| CheckValue<IkReal> x2010=IKPowWithIntegerCheck(IKsign((((npy*x2007))+((npx*x2009)))),-1); |
| if(!x2010.valid){ |
| continue; |
| } |
| 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); |
| if(!x2011.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x2010.value)))+(x2011.value)); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[5]; |
| IkReal x2012=IKsin(j5); |
| IkReal x2013=IKcos(j5); |
| IkReal x2014=((0.416)*sj3); |
| IkReal x2015=(npy*x2012); |
| IkReal x2016=((1.0)*x2013); |
| evalcond[0]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x2012))+(((-1.0)*npy*x2016))); |
| evalcond[1]=((0.02075)+x2015+(((-1.0)*npx*x2016))+(((-1.0)*sj4*x2014))); |
| evalcond[2]=((-0.2602414375)+(((-0.0415)*npx*x2013))+(((0.0415)*x2015))+(((-0.246272)*cj3))+pp); |
| evalcond[3]=((((0.02075)*cj4))+((npz*sj4))+(((-1.0)*cj4*npx*x2016))+((cj4*x2015))); |
| evalcond[4]=((((-1.0)*x2014))+((sj4*x2015))+(((-1.0)*cj4*npz))+(((0.02075)*sj4))+(((-1.0)*npx*sj4*x2016))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j5array[1], cj5array[1], sj5array[1]; |
| bool j5valid[1]={false}; |
| _nj5 = 1; |
| IkReal x2017=((0.416)*cj3); |
| IkReal x2018=((0.416)*sj3*sj4); |
| 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); |
| if(!x2019.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x2020=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| if(!x2020.valid){ |
| continue; |
| } |
| j5array[0]=((-1.5707963267949)+(x2019.value)+(((1.5707963267949)*(x2020.value)))); |
| sj5array[0]=IKsin(j5array[0]); |
| cj5array[0]=IKcos(j5array[0]); |
| if( j5array[0] > IKPI ) |
| { |
| j5array[0]-=IK2PI; |
| } |
| else if( j5array[0] < -IKPI ) |
| { j5array[0]+=IK2PI; |
| } |
| j5valid[0] = true; |
| for(int ij5 = 0; ij5 < 1; ++ij5) |
| { |
| if( !j5valid[ij5] ) |
| { |
| continue; |
| } |
| _ij5[0] = ij5; _ij5[1] = -1; |
| for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| { |
| if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j5valid[iij5]=false; _ij5[1] = iij5; break; |
| } |
| } |
| j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| { |
| IkReal evalcond[5]; |
| IkReal x2021=IKsin(j5); |
| IkReal x2022=IKcos(j5); |
| IkReal x2023=((0.416)*sj3); |
| IkReal x2024=(npy*x2021); |
| IkReal x2025=((1.0)*x2022); |
| evalcond[0]=((-0.296)+(((-1.0)*npx*x2021))+(((-0.416)*cj3))+(((-1.0)*npy*x2025))); |
| evalcond[1]=((0.02075)+x2024+(((-1.0)*sj4*x2023))+(((-1.0)*npx*x2025))); |
| evalcond[2]=((-0.2602414375)+(((0.0415)*x2024))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x2022))); |
| evalcond[3]=((((-1.0)*cj4*npx*x2025))+((cj4*x2024))+(((0.02075)*cj4))+((npz*sj4))); |
| evalcond[4]=((((-1.0)*cj4*npz))+(((-1.0)*npx*sj4*x2025))+(((-1.0)*x2023))+(((0.02075)*sj4))+((sj4*x2024))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| rotationfunction0(solutions); |
| } |
| } |
| |
| } |
| |
| } |
| } |
| } |
| |
| } |
| |
| } |
| } |
| |
| } |
| |
| } |
| } |
| return solutions.GetNumSolutions()>0; |
| } |
| inline void rotationfunction0(IkSolutionListBase<IkReal>& solutions) { |
| for(int rotationiter = 0; rotationiter < 1; ++rotationiter) { |
| IkReal x91=((1.0)*sj3); |
| IkReal x92=((1.0)*sj5); |
| IkReal x93=((1.0)*cj5); |
| IkReal x94=((1.0)*sj4); |
| IkReal x95=((((-1.0)*r01*x92))+((cj5*r00))); |
| IkReal x96=(((cj5*r10))+(((-1.0)*r11*x92))); |
| IkReal x97=(((cj5*r20))+(((-1.0)*r21*x92))); |
| IkReal x98=((((-1.0)*r01*x93))+(((-1.0)*r00*x92))); |
| IkReal x99=((((-1.0)*r11*x93))+(((-1.0)*r10*x92))); |
| IkReal x100=((((-1.0)*r21*x93))+(((-1.0)*r20*x92))); |
| IkReal x101=(((sj4*x95))+((cj4*r02))); |
| IkReal x102=(((sj4*x96))+((cj4*r12))); |
| IkReal x103=(((cj4*r22))+((sj4*x97))); |
| new_r00=(((cj4*x95))+(((-1.0)*r02*x94))); |
| new_r01=(((sj3*x98))+((cj3*x101))); |
| new_r02=(((cj3*x98))+(((-1.0)*x101*x91))); |
| new_r10=((((-1.0)*r12*x94))+((cj4*x96))); |
| new_r11=(((sj3*x99))+((cj3*x102))); |
| new_r12=((((-1.0)*x102*x91))+((cj3*x99))); |
| new_r20=((((-1.0)*r22*x94))+((cj4*x97))); |
| new_r21=(((cj3*x103))+((sj3*x100))); |
| new_r22=((((-1.0)*x103*x91))+((cj3*x100))); |
| { |
| IkReal j1array[2], cj1array[2], sj1array[2]; |
| bool j1valid[2]={false}; |
| _nj1 = 2; |
| sj1array[0]=new_r22; |
| if( sj1array[0] >= -1-IKFAST_SINCOS_THRESH && sj1array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j1valid[0] = j1valid[1] = true; |
| j1array[0] = IKasin(sj1array[0]); |
| cj1array[0] = IKcos(j1array[0]); |
| sj1array[1] = sj1array[0]; |
| j1array[1] = j1array[0] > 0 ? (IKPI-j1array[0]) : (-IKPI-j1array[0]); |
| cj1array[1] = -cj1array[0]; |
| } |
| else if( isnan(sj1array[0]) ) |
| { |
| // probably any value will work |
| j1valid[0] = true; |
| cj1array[0] = 1; sj1array[0] = 0; j1array[0] = 0; |
| } |
| for(int ij1 = 0; ij1 < 2; ++ij1) |
| { |
| if( !j1valid[ij1] ) |
| { |
| continue; |
| } |
| _ij1[0] = ij1; _ij1[1] = -1; |
| for(int iij1 = ij1+1; iij1 < 2; ++iij1) |
| { |
| if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j1valid[iij1]=false; _ij1[1] = iij1; break; |
| } |
| } |
| j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1]; |
| |
| { |
| IkReal j0eval[3]; |
| j0eval[0]=cj1; |
| j0eval[1]=IKsign(cj1); |
| j0eval[2]=((IKabs(new_r12))+(IKabs(new_r02))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2eval[3]; |
| j2eval[0]=cj1; |
| j2eval[1]=IKsign(cj1); |
| j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| j0eval[0]=cj1; |
| j0eval[1]=new_r12; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[5]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r02; |
| evalcond[2]=new_r12; |
| evalcond[3]=new_r20; |
| evalcond[4]=new_r21; |
| 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 ) |
| { |
| bgotonextstatement=false; |
| IkReal j2mul = 1; |
| j2=0; |
| j0mul=-1.0; |
| 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 ) |
| continue; |
| j0=IKatan2(((-1.0)*new_r00), ((-1.0)*new_r01)); |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].fmul = j0mul; |
| vinfos[0].freeind = 0; |
| vinfos[0].maxsolutions = 0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].fmul = j2mul; |
| vinfos[2].freeind = 0; |
| vinfos[2].maxsolutions = 0; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(1); |
| vfree[0] = 2; |
| solutions.AddSolution(vinfos,vfree); |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r02; |
| evalcond[2]=new_r12; |
| evalcond[3]=new_r20; |
| evalcond[4]=new_r21; |
| 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 ) |
| { |
| bgotonextstatement=false; |
| IkReal j2mul = 1; |
| j2=0; |
| j0mul=1.0; |
| 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 ) |
| continue; |
| j0=IKatan2(((-1.0)*new_r00), new_r01); |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].fmul = j0mul; |
| vinfos[0].freeind = 0; |
| vinfos[0].maxsolutions = 0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].fmul = j2mul; |
| vinfos[2].freeind = 0; |
| vinfos[2].maxsolutions = 0; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(1); |
| vfree[0] = 2; |
| solutions.AddSolution(vinfos,vfree); |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| IkReal x104=new_r22*new_r22; |
| IkReal x105=((16.0)*new_r11); |
| IkReal x106=((16.0)*new_r00); |
| IkReal x107=((16.0)*new_r01); |
| IkReal x108=(new_r10*new_r22); |
| IkReal x109=((8.0)*new_r01); |
| IkReal x110=((16.0)*x104); |
| IkReal x111=(x104*x105); |
| IkReal x112=(x104*x106); |
| 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)))); |
| if( IKabs(j0eval[0]) < 0.0000000100000000 ) |
| { |
| continue; // no branches [j0, j2] |
| |
| } else |
| { |
| IkReal op[4+1], zeror[4]; |
| int numroots; |
| IkReal j0evalpoly[1]; |
| IkReal x113=new_r22*new_r22; |
| IkReal x114=((16.0)*new_r11); |
| IkReal x115=(new_r10*new_r22); |
| IkReal x116=(x113*x114); |
| IkReal x117=((((8.0)*x115))+(((8.0)*new_r01))); |
| op[0]=x117; |
| op[1]=((((-1.0)*x114))+x116); |
| op[2]=((((16.0)*x115))+(((-16.0)*new_r01))+(((32.0)*new_r01*x113))); |
| op[3]=((((-1.0)*x116))+x114); |
| op[4]=x117; |
| polyroots4(op,zeror,numroots); |
| IkReal j0array[4], cj0array[4], sj0array[4], tempj0array[1]; |
| int numsolutions = 0; |
| for(int ij0 = 0; ij0 < numroots; ++ij0) |
| { |
| IkReal htj0 = zeror[ij0]; |
| tempj0array[0]=((2.0)*(atan(htj0))); |
| for(int kj0 = 0; kj0 < 1; ++kj0) |
| { |
| j0array[numsolutions] = tempj0array[kj0]; |
| if( j0array[numsolutions] > IKPI ) |
| { |
| j0array[numsolutions]-=IK2PI; |
| } |
| else if( j0array[numsolutions] < -IKPI ) |
| { |
| j0array[numsolutions]+=IK2PI; |
| } |
| sj0array[numsolutions] = IKsin(j0array[numsolutions]); |
| cj0array[numsolutions] = IKcos(j0array[numsolutions]); |
| numsolutions++; |
| } |
| } |
| bool j0valid[4]={true,true,true,true}; |
| _nj0 = 4; |
| for(int ij0 = 0; ij0 < numsolutions; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| htj0 = IKtan(j0/2); |
| |
| IkReal x118=new_r22*new_r22; |
| IkReal x119=((16.0)*new_r00); |
| IkReal x120=(new_r01*new_r22); |
| IkReal x121=((8.0)*x120); |
| IkReal x122=((16.0)*x118); |
| IkReal x123=(x118*x119); |
| IkReal x124=((8.0)*new_r10*x118); |
| IkReal x125=(x124+x121); |
| 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))))); |
| if( IKabs(j0evalpoly[0]) > 0.0000001000000000 ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < numsolutions; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| { |
| IkReal j2eval[3]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| IkReal x126=cj0*cj0; |
| IkReal x127=((1.0)*new_r00); |
| IkReal x128=(cj0*new_r22); |
| IkReal x129=((1.0)+((x126*(new_r22*new_r22)))+(((-1.0)*x126))); |
| j2eval[0]=x129; |
| j2eval[1]=((IKabs((((new_r01*sj0))+(((-1.0)*x127*x128)))))+(IKabs(((((-1.0)*new_r01*x128))+(((-1.0)*sj0*x127)))))); |
| j2eval[2]=IKsign(x129); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| j2eval[0]=new_r22; |
| if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2eval[2]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| IkReal x130=new_r22*new_r22; |
| j2eval[0]=(((cj0*x130))+(((-1.0)*cj0))); |
| j2eval[1]=((((-1.0)*sj0))+((sj0*x130))); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[1]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j0)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(new_r01, ((-1.0)*new_r00)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[4]; |
| IkReal x131=IKcos(j2); |
| IkReal x132=IKsin(j2); |
| evalcond[0]=(x131+new_r00); |
| evalcond[1]=((-1.0)*x132); |
| evalcond[2]=((-1.0)*x131); |
| evalcond[3]=(x132+(((-1.0)*new_r01))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j0)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((-1.0)*new_r01), new_r00); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[4]; |
| IkReal x133=IKsin(j2); |
| IkReal x134=IKcos(j2); |
| evalcond[0]=(x133+new_r01); |
| evalcond[1]=((-1.0)*x133); |
| evalcond[2]=((-1.0)*x134); |
| evalcond[3]=(x134+(((-1.0)*new_r00))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((-1.0)*new_r11), new_r10); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[4]; |
| IkReal x135=IKsin(j2); |
| IkReal x136=IKcos(j2); |
| evalcond[0]=(x135+new_r11); |
| evalcond[1]=((-1.0)*x135); |
| evalcond[2]=((-1.0)*x136); |
| evalcond[3]=(x136+(((-1.0)*new_r10))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[4]; |
| IkReal x137=IKcos(j2); |
| IkReal x138=IKsin(j2); |
| evalcond[0]=(x137+new_r10); |
| evalcond[1]=((-1.0)*x138); |
| evalcond[2]=((-1.0)*x137); |
| evalcond[3]=(x138+(((-1.0)*new_r11))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| CheckValue<IkReal> x139=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| if(!x139.valid){ |
| continue; |
| } |
| if((((-1.0)*(x139.value))) < -0.00001) |
| continue; |
| IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x139.value))))); |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((((-1.0)*gconst40))+cj0)))+(IKabs(((-1.0)+(IKsign(sj0)))))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001) |
| continue; |
| sj0=IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))); |
| cj0=gconst40; |
| if( (gconst40) < -1-IKFAST_SINCOS_THRESH || (gconst40) > 1+IKFAST_SINCOS_THRESH ) |
| continue; |
| j0=IKacos(gconst40); |
| CheckValue<IkReal> x140=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| if(!x140.valid){ |
| continue; |
| } |
| if((((-1.0)*(x140.value))) < -0.00001) |
| continue; |
| IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x140.value))))); |
| j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x141=IKPowWithIntegerCheck(gconst40,-1); |
| if(!x141.valid){ |
| continue; |
| } |
| if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001) |
| continue; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((-1.0)*new_r11*(x141.value)), ((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+((gconst40*new_r10)))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x142=IKsin(j2); |
| IkReal x143=IKcos(j2); |
| IkReal x144=((1.0)*gconst40); |
| if((((1.0)+(((-1.0)*gconst40*x144)))) < -0.00001) |
| continue; |
| IkReal x145=IKsqrt(((1.0)+(((-1.0)*gconst40*x144)))); |
| IkReal x146=((1.0)*x145); |
| evalcond[0]=((-1.0)*x142); |
| evalcond[1]=((-1.0)*x143); |
| evalcond[2]=(((gconst40*x142))+new_r11); |
| evalcond[3]=((((-1.0)*x143*x144))+new_r10); |
| evalcond[4]=(new_r00+((x143*x145))); |
| evalcond[5]=((((-1.0)*x142*x146))+new_r01); |
| evalcond[6]=((((-1.0)*new_r01*x146))+((gconst40*new_r11))+x142); |
| evalcond[7]=(((new_r00*x145))+x143+(((-1.0)*new_r10*x144))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x147=IKPowWithIntegerCheck(IKsign(gconst40),-1); |
| if(!x147.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x148 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x148.valid){ |
| continue; |
| } |
| j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x147.value)))+(x148.value)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x149=IKsin(j2); |
| IkReal x150=IKcos(j2); |
| IkReal x151=((1.0)*gconst40); |
| if((((1.0)+(((-1.0)*gconst40*x151)))) < -0.00001) |
| continue; |
| IkReal x152=IKsqrt(((1.0)+(((-1.0)*gconst40*x151)))); |
| IkReal x153=((1.0)*x152); |
| evalcond[0]=((-1.0)*x149); |
| evalcond[1]=((-1.0)*x150); |
| evalcond[2]=(((gconst40*x149))+new_r11); |
| evalcond[3]=((((-1.0)*x150*x151))+new_r10); |
| evalcond[4]=(((x150*x152))+new_r00); |
| evalcond[5]=(new_r01+(((-1.0)*x149*x153))); |
| evalcond[6]=(((gconst40*new_r11))+x149+(((-1.0)*new_r01*x153))); |
| evalcond[7]=(((new_r00*x152))+x150+(((-1.0)*new_r10*x151))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| CheckValue<IkReal> x154=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| if(!x154.valid){ |
| continue; |
| } |
| if((((-1.0)*(x154.value))) < -0.00001) |
| continue; |
| IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x154.value))))); |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst40))+cj0)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001) |
| continue; |
| sj0=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))); |
| cj0=gconst40; |
| if( (gconst40) < -1-IKFAST_SINCOS_THRESH || (gconst40) > 1+IKFAST_SINCOS_THRESH ) |
| continue; |
| j0=((-1.0)*(IKacos(gconst40))); |
| CheckValue<IkReal> x155=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| if(!x155.valid){ |
| continue; |
| } |
| if((((-1.0)*(x155.value))) < -0.00001) |
| continue; |
| IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x155.value))))); |
| j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001) |
| continue; |
| CheckValue<IkReal> x156=IKPowWithIntegerCheck(gconst40,-1); |
| if(!x156.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+(((-1.0)*gconst40*new_r11))), (new_r10*(x156.value))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x157=IKsin(j2); |
| IkReal x158=IKcos(j2); |
| IkReal x159=((1.0)*gconst40); |
| if((((1.0)+(((-1.0)*gconst40*x159)))) < -0.00001) |
| continue; |
| IkReal x160=IKsqrt(((1.0)+(((-1.0)*gconst40*x159)))); |
| IkReal x161=((1.0)*x160); |
| evalcond[0]=((-1.0)*x157); |
| evalcond[1]=((-1.0)*x158); |
| evalcond[2]=(((gconst40*x157))+new_r11); |
| evalcond[3]=((((-1.0)*x158*x159))+new_r10); |
| evalcond[4]=(((x157*x160))+new_r01); |
| evalcond[5]=((((-1.0)*x158*x161))+new_r00); |
| evalcond[6]=(((new_r01*x160))+((gconst40*new_r11))+x157); |
| evalcond[7]=((((-1.0)*new_r00*x161))+x158+(((-1.0)*new_r10*x159))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x162=IKPowWithIntegerCheck(IKsign(gconst40),-1); |
| if(!x162.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x163 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x163.valid){ |
| continue; |
| } |
| j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x162.value)))+(x163.value)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x164=IKsin(j2); |
| IkReal x165=IKcos(j2); |
| IkReal x166=((1.0)*gconst40); |
| if((((1.0)+(((-1.0)*gconst40*x166)))) < -0.00001) |
| continue; |
| IkReal x167=IKsqrt(((1.0)+(((-1.0)*gconst40*x166)))); |
| IkReal x168=((1.0)*x167); |
| evalcond[0]=((-1.0)*x164); |
| evalcond[1]=((-1.0)*x165); |
| evalcond[2]=(new_r11+((gconst40*x164))); |
| evalcond[3]=(new_r10+(((-1.0)*x165*x166))); |
| evalcond[4]=(((x164*x167))+new_r01); |
| evalcond[5]=(new_r00+(((-1.0)*x165*x168))); |
| evalcond[6]=(((new_r01*x167))+((gconst40*new_r11))+x164); |
| evalcond[7]=((((-1.0)*new_r00*x168))+(((-1.0)*new_r10*x166))+x165); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| CheckValue<IkReal> x169=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| if(!x169.valid){ |
| continue; |
| } |
| if((((-1.0)*(x169.value))) < -0.00001) |
| continue; |
| IkReal gconst41=IKsqrt(((-1.0)*(x169.value))); |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst41))+cj0)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001) |
| continue; |
| sj0=IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))); |
| cj0=gconst41; |
| if( (gconst41) < -1-IKFAST_SINCOS_THRESH || (gconst41) > 1+IKFAST_SINCOS_THRESH ) |
| continue; |
| j0=IKacos(gconst41); |
| CheckValue<IkReal> x170=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| if(!x170.valid){ |
| continue; |
| } |
| if((((-1.0)*(x170.value))) < -0.00001) |
| continue; |
| IkReal gconst41=IKsqrt(((-1.0)*(x170.value))); |
| j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x171=IKPowWithIntegerCheck(gconst41,-1); |
| if(!x171.valid){ |
| continue; |
| } |
| if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001) |
| continue; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((-1.0)*new_r11*(x171.value)), ((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+((gconst41*new_r10)))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x172=IKsin(j2); |
| IkReal x173=IKcos(j2); |
| IkReal x174=((1.0)*gconst41); |
| if((((1.0)+(((-1.0)*gconst41*x174)))) < -0.00001) |
| continue; |
| IkReal x175=IKsqrt(((1.0)+(((-1.0)*gconst41*x174)))); |
| IkReal x176=((1.0)*x175); |
| evalcond[0]=((-1.0)*x172); |
| evalcond[1]=((-1.0)*x173); |
| evalcond[2]=(new_r11+((gconst41*x172))); |
| evalcond[3]=(new_r10+(((-1.0)*x173*x174))); |
| evalcond[4]=(((x173*x175))+new_r00); |
| evalcond[5]=(new_r01+(((-1.0)*x172*x176))); |
| evalcond[6]=(((gconst41*new_r11))+x172+(((-1.0)*new_r01*x176))); |
| evalcond[7]=(((new_r00*x175))+(((-1.0)*new_r10*x174))+x173); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x177=IKPowWithIntegerCheck(IKsign(gconst41),-1); |
| if(!x177.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x178 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x178.valid){ |
| continue; |
| } |
| j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x177.value)))+(x178.value)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x179=IKsin(j2); |
| IkReal x180=IKcos(j2); |
| IkReal x181=((1.0)*gconst41); |
| if((((1.0)+(((-1.0)*gconst41*x181)))) < -0.00001) |
| continue; |
| IkReal x182=IKsqrt(((1.0)+(((-1.0)*gconst41*x181)))); |
| IkReal x183=((1.0)*x182); |
| evalcond[0]=((-1.0)*x179); |
| evalcond[1]=((-1.0)*x180); |
| evalcond[2]=(new_r11+((gconst41*x179))); |
| evalcond[3]=((((-1.0)*x180*x181))+new_r10); |
| evalcond[4]=(((x180*x182))+new_r00); |
| evalcond[5]=(new_r01+(((-1.0)*x179*x183))); |
| evalcond[6]=(((gconst41*new_r11))+x179+(((-1.0)*new_r01*x183))); |
| evalcond[7]=(((new_r00*x182))+x180+(((-1.0)*new_r10*x181))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| CheckValue<IkReal> x184=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| if(!x184.valid){ |
| continue; |
| } |
| if((((-1.0)*(x184.value))) < -0.00001) |
| continue; |
| IkReal gconst41=IKsqrt(((-1.0)*(x184.value))); |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst41))+cj0)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001) |
| continue; |
| sj0=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))); |
| cj0=gconst41; |
| if( (gconst41) < -1-IKFAST_SINCOS_THRESH || (gconst41) > 1+IKFAST_SINCOS_THRESH ) |
| continue; |
| j0=((-1.0)*(IKacos(gconst41))); |
| CheckValue<IkReal> x185=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| if(!x185.valid){ |
| continue; |
| } |
| if((((-1.0)*(x185.value))) < -0.00001) |
| continue; |
| IkReal gconst41=IKsqrt(((-1.0)*(x185.value))); |
| j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001) |
| continue; |
| CheckValue<IkReal> x186=IKPowWithIntegerCheck(gconst41,-1); |
| if(!x186.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+(((-1.0)*gconst41*new_r11))), (new_r10*(x186.value))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x187=IKsin(j2); |
| IkReal x188=IKcos(j2); |
| IkReal x189=((1.0)*gconst41); |
| if((((1.0)+(((-1.0)*gconst41*x189)))) < -0.00001) |
| continue; |
| IkReal x190=IKsqrt(((1.0)+(((-1.0)*gconst41*x189)))); |
| IkReal x191=((1.0)*x190); |
| evalcond[0]=((-1.0)*x187); |
| evalcond[1]=((-1.0)*x188); |
| evalcond[2]=(new_r11+((gconst41*x187))); |
| evalcond[3]=((((-1.0)*x188*x189))+new_r10); |
| evalcond[4]=(((x187*x190))+new_r01); |
| evalcond[5]=((((-1.0)*x188*x191))+new_r00); |
| evalcond[6]=(((new_r01*x190))+((gconst41*new_r11))+x187); |
| evalcond[7]=(x188+(((-1.0)*new_r10*x189))+(((-1.0)*new_r00*x191))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x192=IKPowWithIntegerCheck(IKsign(gconst41),-1); |
| if(!x192.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x193 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x193.valid){ |
| continue; |
| } |
| j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x192.value)))+(x193.value)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x194=IKsin(j2); |
| IkReal x195=IKcos(j2); |
| IkReal x196=((1.0)*gconst41); |
| if((((1.0)+(((-1.0)*gconst41*x196)))) < -0.00001) |
| continue; |
| IkReal x197=IKsqrt(((1.0)+(((-1.0)*gconst41*x196)))); |
| IkReal x198=((1.0)*x197); |
| evalcond[0]=((-1.0)*x194); |
| evalcond[1]=((-1.0)*x195); |
| evalcond[2]=(((gconst41*x194))+new_r11); |
| evalcond[3]=((((-1.0)*x195*x196))+new_r10); |
| evalcond[4]=(((x194*x197))+new_r01); |
| evalcond[5]=((((-1.0)*x195*x198))+new_r00); |
| evalcond[6]=(((new_r01*x197))+((gconst41*new_r11))+x194); |
| evalcond[7]=(x195+(((-1.0)*new_r10*x196))+(((-1.0)*new_r00*x198))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j2] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| IkReal x199=new_r22*new_r22; |
| IkReal x200=((1.0)*new_r22); |
| CheckValue<IkReal> x201=IKPowWithIntegerCheck((((cj0*x199))+(((-1.0)*cj0))),-1); |
| if(!x201.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x202=IKPowWithIntegerCheck(((((-1.0)*sj0))+((sj0*x199))),-1); |
| if(!x202.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((x201.value)*(((((-1.0)*new_r00*x200))+new_r11))), ((x202.value)*((new_r00+(((-1.0)*new_r11*x200)))))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[10]; |
| IkReal x203=IKsin(j2); |
| IkReal x204=IKcos(j2); |
| IkReal x205=((1.0)*sj0); |
| IkReal x206=((1.0)*cj0); |
| IkReal x207=(new_r22*x203); |
| IkReal x208=(new_r22*x204); |
| evalcond[0]=(x203+((cj0*new_r11))+(((-1.0)*new_r01*x205))); |
| evalcond[1]=(((new_r00*sj0))+x204+(((-1.0)*new_r10*x206))); |
| evalcond[2]=(((new_r10*sj0))+x207+((cj0*new_r00))); |
| evalcond[3]=(((new_r11*sj0))+x208+((cj0*new_r01))); |
| evalcond[4]=(((sj0*x204))+((cj0*x207))+new_r00); |
| evalcond[5]=(((sj0*x208))+((cj0*x203))+new_r11); |
| evalcond[6]=((((-1.0)*x203*x205))+((cj0*x208))+new_r01); |
| evalcond[7]=((((-1.0)*x204*x206))+((sj0*x207))+new_r10); |
| evalcond[8]=((((-1.0)*new_r10*new_r22*x205))+(((-1.0)*new_r00*new_r22*x206))+(((-1.0)*x203))); |
| evalcond[9]=((((-1.0)*new_r01*new_r22*x206))+(((-1.0)*new_r11*new_r22*x205))+(((-1.0)*x204))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| IkReal x209=((1.0)*new_r00); |
| CheckValue<IkReal> x210=IKPowWithIntegerCheck(new_r22,-1); |
| if(!x210.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((x210.value)*(((((-1.0)*cj0*x209))+(((-1.0)*new_r10*sj0))))), (((cj0*new_r10))+(((-1.0)*sj0*x209)))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[10]; |
| IkReal x211=IKsin(j2); |
| IkReal x212=IKcos(j2); |
| IkReal x213=((1.0)*sj0); |
| IkReal x214=((1.0)*cj0); |
| IkReal x215=(new_r22*x211); |
| IkReal x216=(new_r22*x212); |
| evalcond[0]=(x211+(((-1.0)*new_r01*x213))+((cj0*new_r11))); |
| evalcond[1]=(((new_r00*sj0))+(((-1.0)*new_r10*x214))+x212); |
| evalcond[2]=(((new_r10*sj0))+x215+((cj0*new_r00))); |
| evalcond[3]=(((new_r11*sj0))+x216+((cj0*new_r01))); |
| evalcond[4]=(((cj0*x215))+((sj0*x212))+new_r00); |
| evalcond[5]=(((cj0*x211))+((sj0*x216))+new_r11); |
| evalcond[6]=(((cj0*x216))+(((-1.0)*x211*x213))+new_r01); |
| evalcond[7]=(((sj0*x215))+new_r10+(((-1.0)*x212*x214))); |
| evalcond[8]=((((-1.0)*x211))+(((-1.0)*new_r00*new_r22*x214))+(((-1.0)*new_r10*new_r22*x213))); |
| evalcond[9]=((((-1.0)*x212))+(((-1.0)*new_r11*new_r22*x213))+(((-1.0)*new_r01*new_r22*x214))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| IkReal x217=cj0*cj0; |
| IkReal x218=((1.0)*new_r00); |
| IkReal x219=(cj0*new_r22); |
| CheckValue<IkReal> x220=IKPowWithIntegerCheck(IKsign(((1.0)+(((-1.0)*x217))+((x217*(new_r22*new_r22))))),-1); |
| if(!x220.valid){ |
| continue; |
| } |
| 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); |
| if(!x221.valid){ |
| continue; |
| } |
| j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x220.value)))+(x221.value)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[10]; |
| IkReal x222=IKsin(j2); |
| IkReal x223=IKcos(j2); |
| IkReal x224=((1.0)*sj0); |
| IkReal x225=((1.0)*cj0); |
| IkReal x226=(new_r22*x222); |
| IkReal x227=(new_r22*x223); |
| evalcond[0]=((((-1.0)*new_r01*x224))+x222+((cj0*new_r11))); |
| evalcond[1]=((((-1.0)*new_r10*x225))+((new_r00*sj0))+x223); |
| evalcond[2]=(((new_r10*sj0))+x226+((cj0*new_r00))); |
| evalcond[3]=(((new_r11*sj0))+x227+((cj0*new_r01))); |
| evalcond[4]=(((sj0*x223))+((cj0*x226))+new_r00); |
| evalcond[5]=(((sj0*x227))+((cj0*x222))+new_r11); |
| evalcond[6]=((((-1.0)*x222*x224))+((cj0*x227))+new_r01); |
| evalcond[7]=(((sj0*x226))+(((-1.0)*x223*x225))+new_r10); |
| evalcond[8]=((((-1.0)*new_r00*new_r22*x225))+(((-1.0)*new_r10*new_r22*x224))+(((-1.0)*x222))); |
| evalcond[9]=((((-1.0)*new_r11*new_r22*x224))+(((-1.0)*new_r01*new_r22*x225))+(((-1.0)*x223))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0, j2] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x229=IKPowWithIntegerCheck(cj1,-1); |
| if(!x229.valid){ |
| continue; |
| } |
| IkReal x228=x229.value; |
| CheckValue<IkReal> x230=IKPowWithIntegerCheck(new_r12,-1); |
| if(!x230.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x231=IKPowWithIntegerCheck(x228,-2); |
| if(!x231.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((x228*(x230.value)*(((((-1.0)*(new_r02*new_r02)))+(x231.value)))), (new_r02*x228)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x232=IKcos(j0); |
| IkReal x233=IKsin(j0); |
| IkReal x234=(cj1*x232); |
| IkReal x235=(cj1*x233); |
| IkReal x236=((1.0)*x233); |
| IkReal x237=(new_r02*x232); |
| evalcond[0]=(new_r02+(((-1.0)*x234))); |
| evalcond[1]=(new_r12+(((-1.0)*x235))); |
| evalcond[2]=((((-1.0)*new_r02*x236))+((new_r12*x232))); |
| evalcond[3]=(((new_r12*x233))+x237+(((-1.0)*cj1))); |
| evalcond[4]=(((new_r10*x235))+((new_r20*sj1))+((new_r00*x234))); |
| evalcond[5]=(((new_r11*x235))+((new_r01*x234))+((new_r21*sj1))); |
| evalcond[6]=((-1.0)+((new_r02*x234))+((new_r12*x235))+((new_r22*sj1))); |
| evalcond[7]=(((cj1*new_r22))+(((-1.0)*sj1*x237))+(((-1.0)*new_r12*sj1*x236))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| IkReal j2eval[3]; |
| j2eval[0]=cj1; |
| j2eval[1]=IKsign(cj1); |
| j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2eval[2]; |
| j2eval[0]=cj1; |
| j2eval[1]=sj0; |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2eval[3]; |
| j2eval[0]=cj1; |
| j2eval[1]=sj0; |
| j2eval[2]=sj1; |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[5]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r02; |
| evalcond[2]=new_r12; |
| evalcond[3]=new_r20; |
| evalcond[4]=new_r21; |
| 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 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| IkReal x238=((1.0)*cj0); |
| 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 ) |
| continue; |
| j2array[0]=IKatan2((((new_r01*sj0))+(((-1.0)*new_r00*x238))), ((((-1.0)*new_r00*sj0))+(((-1.0)*new_r01*x238)))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x239=IKsin(j2); |
| IkReal x240=IKcos(j2); |
| IkReal x241=((1.0)*cj0); |
| IkReal x242=(sj0*x240); |
| IkReal x243=(cj0*x239); |
| IkReal x244=(sj0*x239); |
| IkReal x245=(x243+x242); |
| evalcond[0]=(((new_r10*sj0))+x239+((cj0*new_r00))); |
| evalcond[1]=(((new_r11*sj0))+x240+((cj0*new_r01))); |
| evalcond[2]=((((-1.0)*new_r01*sj0))+x239+((cj0*new_r11))); |
| evalcond[3]=(((new_r00*sj0))+x240+(((-1.0)*new_r10*x241))); |
| evalcond[4]=(x245+new_r00); |
| evalcond[5]=(x245+new_r11); |
| evalcond[6]=(((cj0*x240))+(((-1.0)*x244))+new_r01); |
| evalcond[7]=(x244+(((-1.0)*x240*x241))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r02; |
| evalcond[2]=new_r12; |
| evalcond[3]=new_r20; |
| evalcond[4]=new_r21; |
| 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 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2((((new_r01*sj0))+((cj0*new_r00))), (((cj0*new_r01))+(((-1.0)*new_r00*sj0)))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x246=IKsin(j2); |
| IkReal x247=IKcos(j2); |
| IkReal x248=((1.0)*sj0); |
| IkReal x249=((1.0)*cj0); |
| IkReal x250=((1.0)*x247); |
| IkReal x251=(((x246*x248))+((x247*x249))); |
| evalcond[0]=((((-1.0)*new_r01*x248))+x246+((cj0*new_r11))); |
| evalcond[1]=(((new_r00*sj0))+x247+(((-1.0)*new_r10*x249))); |
| evalcond[2]=((((-1.0)*x246))+((new_r10*sj0))+((cj0*new_r00))); |
| evalcond[3]=(((new_r11*sj0))+((cj0*new_r01))+(((-1.0)*x250))); |
| evalcond[4]=(new_r00+((sj0*x247))+(((-1.0)*x246*x249))); |
| evalcond[5]=(((cj0*x246))+new_r11+(((-1.0)*x247*x248))); |
| evalcond[6]=(new_r01+(((-1.0)*x251))); |
| evalcond[7]=(new_r10+(((-1.0)*x251))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959))); |
| evalcond[1]=new_r12; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((-1.0)*new_r11), new_r10); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x252=IKsin(j2); |
| IkReal x253=IKcos(j2); |
| IkReal x254=((1.0)*sj1); |
| IkReal x255=((1.0)*cj1); |
| evalcond[0]=(x252+new_r11); |
| evalcond[1]=(x253+(((-1.0)*new_r10))); |
| evalcond[2]=(((sj1*x252))+new_r00); |
| evalcond[3]=(((sj1*x253))+new_r01); |
| evalcond[4]=((((-1.0)*x252*x255))+new_r20); |
| evalcond[5]=(new_r21+(((-1.0)*x253*x255))); |
| evalcond[6]=(((cj1*new_r20))+(((-1.0)*new_r00*x254))+(((-1.0)*x252))); |
| evalcond[7]=((((-1.0)*new_r01*x254))+((cj1*new_r21))+(((-1.0)*x253))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959))); |
| evalcond[1]=new_r12; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x256=IKsin(j2); |
| IkReal x257=IKcos(j2); |
| IkReal x258=((1.0)*cj1); |
| evalcond[0]=(x257+new_r10); |
| evalcond[1]=(x256+(((-1.0)*new_r11))); |
| evalcond[2]=((((-1.0)*x256*x258))+new_r20); |
| evalcond[3]=((((-1.0)*x257*x258))+new_r21); |
| evalcond[4]=(((sj1*x256))+(((-1.0)*new_r00))); |
| evalcond[5]=(((sj1*x257))+(((-1.0)*new_r01))); |
| evalcond[6]=(((cj1*new_r20))+((new_r00*sj1))+(((-1.0)*x256))); |
| evalcond[7]=(((cj1*new_r21))+((new_r01*sj1))+(((-1.0)*x257))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j1))), 6.28318530717959))); |
| evalcond[1]=new_r22; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH ) |
| continue; |
| j2array[0]=IKatan2(new_r20, new_r21); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x259=IKcos(j2); |
| IkReal x260=IKsin(j2); |
| IkReal x261=((1.0)*sj0); |
| IkReal x262=((1.0)*x259); |
| evalcond[0]=((((-1.0)*x260))+new_r20); |
| evalcond[1]=(new_r21+(((-1.0)*x262))); |
| evalcond[2]=(((sj0*x259))+new_r00); |
| evalcond[3]=(((cj0*x260))+new_r11); |
| evalcond[4]=(new_r01+(((-1.0)*x260*x261))); |
| evalcond[5]=(new_r10+(((-1.0)*new_r02*x262))); |
| evalcond[6]=((((-1.0)*new_r01*x261))+x260+((cj0*new_r11))); |
| evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x259); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r22; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((-1.0)*new_r20), ((-1.0)*new_r21)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x263=IKcos(j2); |
| IkReal x264=IKsin(j2); |
| IkReal x265=((1.0)*sj0); |
| evalcond[0]=(x264+new_r20); |
| evalcond[1]=(x263+new_r21); |
| evalcond[2]=(new_r00+((sj0*x263))); |
| evalcond[3]=(((cj0*x264))+new_r11); |
| evalcond[4]=(new_r10+((new_r02*x263))); |
| evalcond[5]=(new_r01+(((-1.0)*x264*x265))); |
| evalcond[6]=((((-1.0)*new_r01*x265))+x264+((cj0*new_r11))); |
| evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x263); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2eval[1]; |
| new_r21=0; |
| new_r20=0; |
| new_r02=0; |
| new_r12=0; |
| j2eval[0]=IKabs(new_r22); |
| if( IKabs(j2eval[0]) < 0.0000000100000000 ) |
| { |
| continue; // no branches [j2] |
| |
| } else |
| { |
| IkReal op[2+1], zeror[2]; |
| int numroots; |
| op[0]=((-1.0)*new_r22); |
| op[1]=0; |
| op[2]=new_r22; |
| polyroots2(op,zeror,numroots); |
| IkReal j2array[2], cj2array[2], sj2array[2], tempj2array[1]; |
| int numsolutions = 0; |
| for(int ij2 = 0; ij2 < numroots; ++ij2) |
| { |
| IkReal htj2 = zeror[ij2]; |
| tempj2array[0]=((2.0)*(atan(htj2))); |
| for(int kj2 = 0; kj2 < 1; ++kj2) |
| { |
| j2array[numsolutions] = tempj2array[kj2]; |
| if( j2array[numsolutions] > IKPI ) |
| { |
| j2array[numsolutions]-=IK2PI; |
| } |
| else if( j2array[numsolutions] < -IKPI ) |
| { |
| j2array[numsolutions]+=IK2PI; |
| } |
| sj2array[numsolutions] = IKsin(j2array[numsolutions]); |
| cj2array[numsolutions] = IKcos(j2array[numsolutions]); |
| numsolutions++; |
| } |
| } |
| bool j2valid[2]={true,true}; |
| _nj2 = 2; |
| for(int ij2 = 0; ij2 < numsolutions; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| htj2 = IKtan(j2/2); |
| |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < numsolutions; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j2] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x267=IKPowWithIntegerCheck(cj1,-1); |
| if(!x267.valid){ |
| continue; |
| } |
| IkReal x266=x267.value; |
| CheckValue<IkReal> x268=IKPowWithIntegerCheck(sj0,-1); |
| if(!x268.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x269=IKPowWithIntegerCheck(sj1,-1); |
| if(!x269.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j2array[0]=IKatan2((new_r20*x266), (x266*(x268.value)*(x269.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11)))))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[12]; |
| IkReal x270=IKsin(j2); |
| IkReal x271=IKcos(j2); |
| IkReal x272=((1.0)*sj0); |
| IkReal x273=(cj0*new_r00); |
| IkReal x274=((1.0)*cj0); |
| IkReal x275=((1.0)*x271); |
| IkReal x276=(sj1*x270); |
| IkReal x277=(sj1*x271); |
| IkReal x278=((1.0)*x270); |
| evalcond[0]=((((-1.0)*cj1*x278))+new_r20); |
| evalcond[1]=((((-1.0)*cj1*x275))+new_r21); |
| evalcond[2]=((((-1.0)*new_r01*x272))+x270+((cj0*new_r11))); |
| evalcond[3]=(((new_r00*sj0))+x271+(((-1.0)*new_r10*x274))); |
| evalcond[4]=(((new_r10*sj0))+x276+x273); |
| evalcond[5]=(((new_r11*sj0))+x277+((cj0*new_r01))); |
| evalcond[6]=(new_r00+((sj0*x271))+((cj0*x276))); |
| evalcond[7]=(new_r11+((sj0*x277))+((cj0*x270))); |
| evalcond[8]=((((-1.0)*x270*x272))+new_r01+((cj0*x277))); |
| evalcond[9]=((((-1.0)*x271*x274))+new_r10+((sj0*x276))); |
| evalcond[10]=((((-1.0)*new_r10*sj1*x272))+((cj1*new_r20))+(((-1.0)*sj1*x273))+(((-1.0)*x278))); |
| evalcond[11]=(((cj1*new_r21))+(((-1.0)*x275))+(((-1.0)*new_r11*sj1*x272))+(((-1.0)*new_r01*sj1*x274))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x280=IKPowWithIntegerCheck(cj1,-1); |
| if(!x280.valid){ |
| continue; |
| } |
| IkReal x279=x280.value; |
| CheckValue<IkReal> x281=IKPowWithIntegerCheck(sj0,-1); |
| if(!x281.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j2array[0]=IKatan2((new_r20*x279), (x279*(x281.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00)))))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[12]; |
| IkReal x282=IKsin(j2); |
| IkReal x283=IKcos(j2); |
| IkReal x284=((1.0)*sj0); |
| IkReal x285=(cj0*new_r00); |
| IkReal x286=((1.0)*cj0); |
| IkReal x287=((1.0)*x283); |
| IkReal x288=(sj1*x282); |
| IkReal x289=(sj1*x283); |
| IkReal x290=((1.0)*x282); |
| evalcond[0]=((((-1.0)*cj1*x290))+new_r20); |
| evalcond[1]=((((-1.0)*cj1*x287))+new_r21); |
| evalcond[2]=(x282+(((-1.0)*new_r01*x284))+((cj0*new_r11))); |
| evalcond[3]=(((new_r00*sj0))+x283+(((-1.0)*new_r10*x286))); |
| evalcond[4]=(((new_r10*sj0))+x288+x285); |
| evalcond[5]=(((new_r11*sj0))+x289+((cj0*new_r01))); |
| evalcond[6]=(((cj0*x288))+((sj0*x283))+new_r00); |
| evalcond[7]=(((cj0*x282))+((sj0*x289))+new_r11); |
| evalcond[8]=(((cj0*x289))+(((-1.0)*x282*x284))+new_r01); |
| evalcond[9]=(((sj0*x288))+new_r10+(((-1.0)*x283*x286))); |
| evalcond[10]=(((cj1*new_r20))+(((-1.0)*x290))+(((-1.0)*new_r10*sj1*x284))+(((-1.0)*sj1*x285))); |
| evalcond[11]=((((-1.0)*new_r01*sj1*x286))+((cj1*new_r21))+(((-1.0)*new_r11*sj1*x284))+(((-1.0)*x287))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x291=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| if(!x291.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x292 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); |
| if(!x292.valid){ |
| continue; |
| } |
| j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x291.value)))+(x292.value)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[12]; |
| IkReal x293=IKsin(j2); |
| IkReal x294=IKcos(j2); |
| IkReal x295=((1.0)*sj0); |
| IkReal x296=(cj0*new_r00); |
| IkReal x297=((1.0)*cj0); |
| IkReal x298=((1.0)*x294); |
| IkReal x299=(sj1*x293); |
| IkReal x300=(sj1*x294); |
| IkReal x301=((1.0)*x293); |
| evalcond[0]=((((-1.0)*cj1*x301))+new_r20); |
| evalcond[1]=((((-1.0)*cj1*x298))+new_r21); |
| evalcond[2]=((((-1.0)*new_r01*x295))+x293+((cj0*new_r11))); |
| evalcond[3]=((((-1.0)*new_r10*x297))+((new_r00*sj0))+x294); |
| evalcond[4]=(((new_r10*sj0))+x299+x296); |
| evalcond[5]=(((new_r11*sj0))+x300+((cj0*new_r01))); |
| evalcond[6]=(((sj0*x294))+new_r00+((cj0*x299))); |
| evalcond[7]=(((sj0*x300))+new_r11+((cj0*x293))); |
| evalcond[8]=((((-1.0)*x293*x295))+((cj0*x300))+new_r01); |
| evalcond[9]=(((sj0*x299))+new_r10+(((-1.0)*x294*x297))); |
| evalcond[10]=((((-1.0)*new_r10*sj1*x295))+(((-1.0)*sj1*x296))+((cj1*new_r20))+(((-1.0)*x301))); |
| evalcond[11]=((((-1.0)*new_r11*sj1*x295))+((cj1*new_r21))+(((-1.0)*x298))+(((-1.0)*new_r01*sj1*x297))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x302=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| if(!x302.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x303 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); |
| if(!x303.valid){ |
| continue; |
| } |
| j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x302.value)))+(x303.value)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[2]; |
| IkReal x304=((1.0)*cj1); |
| evalcond[0]=((((-1.0)*x304*(IKsin(j2))))+new_r20); |
| evalcond[1]=((((-1.0)*x304*(IKcos(j2))))+new_r21); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| IkReal j0eval[3]; |
| j0eval[0]=cj1; |
| j0eval[1]=IKsign(cj1); |
| j0eval[2]=((IKabs(new_r12))+(IKabs(new_r02))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| j0eval[0]=cj1; |
| j0eval[1]=new_r01; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[5]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r02; |
| evalcond[2]=new_r12; |
| evalcond[3]=new_r20; |
| evalcond[4]=new_r21; |
| 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 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| IkReal x305=(((new_r00*new_r11))+(((-1.0)*new_r01*new_r10))); |
| j0eval[0]=x305; |
| j0eval[1]=((IKabs((((new_r01*sj2))+(((-1.0)*cj2*new_r00)))))+(IKabs((((cj2*new_r10))+(((-1.0)*new_r11*sj2)))))); |
| j0eval[2]=IKsign(x305); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| IkReal x306=(((cj2*new_r01))+(((-1.0)*new_r11*sj2))); |
| j0eval[0]=x306; |
| j0eval[1]=((IKabs((((cj2*sj2))+(((-1.0)*new_r00*new_r01)))))+(IKabs(((((-1.0)*(cj2*cj2)))+((new_r00*new_r11)))))); |
| j0eval[2]=IKsign(x306); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| IkReal x307=((1.0)*sj2); |
| IkReal x308=(((cj2*new_r00))+(((-1.0)*new_r10*x307))); |
| j0eval[0]=x308; |
| j0eval[1]=IKsign(x308); |
| j0eval[2]=((IKabs(((((-1.0)*cj2*x307))+((new_r10*new_r11)))))+(IKabs(((1.0)+(((-1.0)*(cj2*cj2)))+(((-1.0)*new_r00*new_r11)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[1]; |
| bool bgotonextstatement = true; |
| do |
| { |
| IkReal x311 = ((new_r10*new_r10)+(new_r00*new_r00)); |
| if(IKabs(x311)==0){ |
| continue; |
| } |
| IkReal x309=pow(x311,-0.5); |
| IkReal x310=((-1.0)*x309); |
| CheckValue<IkReal> x312 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x312.valid){ |
| continue; |
| } |
| IkReal gconst16=((-1.0)*(x312.value)); |
| IkReal gconst17=(new_r00*x310); |
| IkReal gconst18=(new_r10*x310); |
| CheckValue<IkReal> x313 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x313.valid){ |
| continue; |
| } |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x313.value)+j2)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x317 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x317.valid){ |
| continue; |
| } |
| IkReal x314=((-1.0)*(x317.value)); |
| IkReal x315=x309; |
| IkReal x316=((-1.0)*x315); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x314; |
| IkReal gconst16=x314; |
| IkReal gconst17=(new_r00*x316); |
| IkReal gconst18=(new_r10*x316); |
| IkReal x318=new_r10*new_r10; |
| IkReal x319=(new_r00*new_r11); |
| IkReal x320=(x319+(((-1.0)*new_r01*new_r10))); |
| IkReal x321=x309; |
| IkReal x322=((1.0)*x321); |
| j0eval[0]=x320; |
| j0eval[1]=IKsign(x320); |
| j0eval[2]=((IKabs((((new_r00*new_r10*x321))+(((-1.0)*new_r00*new_r01*x322)))))+(IKabs(((((-1.0)*x318*x322))+((x319*x321)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x326 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x326.valid){ |
| continue; |
| } |
| IkReal x323=((-1.0)*(x326.value)); |
| IkReal x324=x309; |
| IkReal x325=((-1.0)*x324); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x323; |
| IkReal gconst16=x323; |
| IkReal gconst17=(new_r00*x325); |
| IkReal gconst18=(new_r10*x325); |
| IkReal x327=new_r10*new_r10; |
| IkReal x328=((1.0)*new_r00); |
| CheckValue<IkReal> x331=IKPowWithIntegerCheck((x327+(new_r00*new_r00)),-1); |
| if(!x331.valid){ |
| continue; |
| } |
| IkReal x329=x331.value; |
| IkReal x330=(x327*x329); |
| 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)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x335 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x335.valid){ |
| continue; |
| } |
| IkReal x332=((-1.0)*(x335.value)); |
| IkReal x333=x309; |
| IkReal x334=((-1.0)*x333); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x332; |
| IkReal gconst16=x332; |
| IkReal gconst17=(new_r00*x334); |
| IkReal gconst18=(new_r10*x334); |
| IkReal x336=new_r00*new_r00; |
| IkReal x337=(new_r00*new_r01); |
| IkReal x338=(((new_r10*new_r11))+x337); |
| IkReal x339=x309; |
| IkReal x340=(new_r00*x339); |
| j0eval[0]=x338; |
| j0eval[1]=IKsign(x338); |
| j0eval[2]=((IKabs((((new_r11*x340))+(((-1.0)*x336*x339)))))+(IKabs((((x337*x339))+((new_r10*x340)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[3]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| IkReal x341=((-1.0)*new_r10); |
| CheckValue<IkReal> x343 = IKatan2WithCheck(IkReal(0),IkReal(x341),IKFAST_ATAN2_MAGTHRESH); |
| if(!x343.valid){ |
| continue; |
| } |
| IkReal x342=((-1.0)*(x343.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x342; |
| new_r11=0; |
| new_r00=0; |
| IkReal gconst16=x342; |
| IkReal gconst17=0; |
| IkReal x344 = new_r10*new_r10; |
| if(IKabs(x344)==0){ |
| continue; |
| } |
| IkReal gconst18=(x341*(pow(x344,-0.5))); |
| j0eval[0]=new_r10; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x345=IKPowWithIntegerCheck(gconst18,-1); |
| if(!x345.valid){ |
| continue; |
| } |
| cj0array[0]=(new_r10*(x345.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x346=IKsin(j0); |
| IkReal x347=IKcos(j0); |
| evalcond[0]=(new_r10*x346); |
| evalcond[1]=(gconst18*x346); |
| evalcond[2]=((-1.0)*new_r01*x346); |
| evalcond[3]=(gconst18+((new_r01*x347))); |
| evalcond[4]=(((gconst18*x347))+new_r01); |
| evalcond[5]=(gconst18+(((-1.0)*new_r10*x347))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x348=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x348.valid){ |
| continue; |
| } |
| cj0array[0]=(gconst18*(x348.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x349=IKsin(j0); |
| IkReal x350=IKcos(j0); |
| IkReal x351=(gconst18*x350); |
| evalcond[0]=(new_r10*x349); |
| evalcond[1]=(gconst18*x349); |
| evalcond[2]=((-1.0)*new_r01*x349); |
| evalcond[3]=(((new_r01*x350))+gconst18); |
| evalcond[4]=(x351+new_r01); |
| evalcond[5]=((((-1.0)*x351))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| evalcond[1]=gconst17; |
| evalcond[2]=gconst18; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| IkReal x352=((-1.0)*new_r10); |
| CheckValue<IkReal> x354 = IKatan2WithCheck(IkReal(new_r00),IkReal(x352),IKFAST_ATAN2_MAGTHRESH); |
| if(!x354.valid){ |
| continue; |
| } |
| IkReal x353=((-1.0)*(x354.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x353; |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst16=x353; |
| IkReal gconst17=((-1.0)*new_r00); |
| IkReal gconst18=x352; |
| j0eval[0]=1.0; |
| j0eval[1]=1.0; |
| j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x355=((-1.0)*new_r10); |
| CheckValue<IkReal> x357 = IKatan2WithCheck(IkReal(new_r00),IkReal(x355),IKFAST_ATAN2_MAGTHRESH); |
| if(!x357.valid){ |
| continue; |
| } |
| IkReal x356=((-1.0)*(x357.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x356; |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst16=x356; |
| IkReal gconst17=((-1.0)*new_r00); |
| IkReal gconst18=x355; |
| j0eval[0]=1.0; |
| j0eval[1]=1.0; |
| j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x358=((-1.0)*new_r10); |
| CheckValue<IkReal> x360 = IKatan2WithCheck(IkReal(new_r00),IkReal(x358),IKFAST_ATAN2_MAGTHRESH); |
| if(!x360.valid){ |
| continue; |
| } |
| IkReal x359=((-1.0)*(x360.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x359; |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst16=x359; |
| IkReal gconst17=((-1.0)*new_r00); |
| IkReal gconst18=x358; |
| j0eval[0]=-1.0; |
| j0eval[1]=-1.0; |
| j0eval[2]=((IKabs(((-1.0)+(new_r10*new_r10))))+(IKabs((new_r00*new_r10)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x361=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst17*gconst17)))+(((-1.0)*(gconst18*gconst18))))),-1); |
| if(!x361.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x362 = IKatan2WithCheck(IkReal((gconst18*new_r00)),IkReal((gconst17*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x362.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x361.value)))+(x362.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x363=IKcos(j0); |
| IkReal x364=IKsin(j0); |
| IkReal x365=(gconst17*x363); |
| IkReal x366=(gconst18*x364); |
| IkReal x367=((1.0)*x363); |
| IkReal x368=(gconst17*x364); |
| IkReal x369=(x365+x366); |
| evalcond[0]=x369; |
| evalcond[1]=(gconst17+((new_r00*x363))+((new_r10*x364))); |
| evalcond[2]=(x369+new_r00); |
| evalcond[3]=(((gconst18*x363))+(((-1.0)*x368))); |
| evalcond[4]=(gconst18+((new_r00*x364))+(((-1.0)*new_r10*x367))); |
| evalcond[5]=((((-1.0)*gconst18*x367))+x368+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x370 = IKatan2WithCheck(IkReal((gconst17*gconst18)),IkReal(((-1.0)*(gconst18*gconst18))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x370.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x371=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst17*new_r00))+(((-1.0)*gconst18*new_r10)))),-1); |
| if(!x371.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x370.value)+(((1.5707963267949)*(x371.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x372=IKcos(j0); |
| IkReal x373=IKsin(j0); |
| IkReal x374=(gconst17*x372); |
| IkReal x375=(gconst18*x373); |
| IkReal x376=((1.0)*x372); |
| IkReal x377=(gconst17*x373); |
| IkReal x378=(x375+x374); |
| evalcond[0]=x378; |
| evalcond[1]=(gconst17+((new_r00*x372))+((new_r10*x373))); |
| evalcond[2]=(x378+new_r00); |
| evalcond[3]=((((-1.0)*x377))+((gconst18*x372))); |
| evalcond[4]=(gconst18+((new_r00*x373))+(((-1.0)*new_r10*x376))); |
| evalcond[5]=((((-1.0)*gconst18*x376))+x377+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x379 = IKatan2WithCheck(IkReal((gconst17*gconst18)),IkReal(gconst17*gconst17),IKFAST_ATAN2_MAGTHRESH); |
| if(!x379.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x380=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst17*new_r00))+(((-1.0)*gconst18*new_r10)))),-1); |
| if(!x380.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x379.value)+(((1.5707963267949)*(x380.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x381=IKcos(j0); |
| IkReal x382=IKsin(j0); |
| IkReal x383=(gconst17*x381); |
| IkReal x384=(gconst18*x382); |
| IkReal x385=((1.0)*x381); |
| IkReal x386=(gconst17*x382); |
| IkReal x387=(x384+x383); |
| evalcond[0]=x387; |
| evalcond[1]=(((new_r00*x381))+gconst17+((new_r10*x382))); |
| evalcond[2]=(x387+new_r00); |
| evalcond[3]=((((-1.0)*x386))+((gconst18*x381))); |
| evalcond[4]=((((-1.0)*new_r10*x385))+((new_r00*x382))+gconst18); |
| evalcond[5]=(x386+(((-1.0)*gconst18*x385))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x389 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x389.valid){ |
| continue; |
| } |
| IkReal x388=((-1.0)*(x389.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x388; |
| new_r01=0; |
| new_r10=0; |
| IkReal gconst16=x388; |
| IkReal x390 = new_r00*new_r00; |
| if(IKabs(x390)==0){ |
| continue; |
| } |
| IkReal gconst17=((-1.0)*new_r00*(pow(x390,-0.5))); |
| IkReal gconst18=0; |
| j0eval[0]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x392 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x392.valid){ |
| continue; |
| } |
| IkReal x391=((-1.0)*(x392.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x391; |
| new_r01=0; |
| new_r10=0; |
| IkReal gconst16=x391; |
| IkReal x393 = new_r00*new_r00; |
| if(IKabs(x393)==0){ |
| continue; |
| } |
| IkReal gconst17=((-1.0)*new_r00*(pow(x393,-0.5))); |
| IkReal gconst18=0; |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x394=IKPowWithIntegerCheck(gconst17,-1); |
| if(!x394.valid){ |
| continue; |
| } |
| cj0array[0]=((-1.0)*new_r00*(x394.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x395=IKsin(j0); |
| IkReal x396=IKcos(j0); |
| evalcond[0]=(new_r00*x395); |
| evalcond[1]=(new_r11*x395); |
| evalcond[2]=((-1.0)*gconst17*x395); |
| evalcond[3]=(((new_r11*x396))+gconst17); |
| evalcond[4]=(gconst17+((new_r00*x396))); |
| evalcond[5]=(new_r11+((gconst17*x396))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x397=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x397.valid){ |
| continue; |
| } |
| cj0array[0]=((-1.0)*gconst17*(x397.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x398=IKsin(j0); |
| IkReal x399=IKcos(j0); |
| IkReal x400=(gconst17*x399); |
| evalcond[0]=(new_r00*x398); |
| evalcond[1]=(new_r11*x398); |
| evalcond[2]=((-1.0)*gconst17*x398); |
| evalcond[3]=(((new_r11*x399))+gconst17); |
| evalcond[4]=(x400+new_r00); |
| evalcond[5]=(x400+new_r11); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x401=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x401.valid){ |
| continue; |
| } |
| cj0array[0]=((-1.0)*gconst17*(x401.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x402=IKsin(j0); |
| IkReal x403=IKcos(j0); |
| IkReal x404=(gconst17*x403); |
| evalcond[0]=(new_r00*x402); |
| evalcond[1]=(new_r11*x402); |
| evalcond[2]=((-1.0)*gconst17*x402); |
| evalcond[3]=(gconst17+((new_r00*x403))); |
| evalcond[4]=(x404+new_r00); |
| evalcond[5]=(x404+new_r11); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=IKabs(new_r00); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| IkReal x405=((-1.0)*new_r10); |
| CheckValue<IkReal> x407 = IKatan2WithCheck(IkReal(0),IkReal(x405),IKFAST_ATAN2_MAGTHRESH); |
| if(!x407.valid){ |
| continue; |
| } |
| IkReal x406=((-1.0)*(x407.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x406; |
| new_r00=0; |
| IkReal gconst16=x406; |
| IkReal gconst17=0; |
| IkReal x408 = new_r10*new_r10; |
| if(IKabs(x408)==0){ |
| continue; |
| } |
| IkReal gconst18=(x405*(pow(x408,-0.5))); |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x409=((-1.0)*new_r10); |
| CheckValue<IkReal> x411 = IKatan2WithCheck(IkReal(0),IkReal(x409),IKFAST_ATAN2_MAGTHRESH); |
| if(!x411.valid){ |
| continue; |
| } |
| IkReal x410=((-1.0)*(x411.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x410; |
| new_r00=0; |
| IkReal gconst16=x410; |
| IkReal gconst17=0; |
| IkReal x412 = new_r10*new_r10; |
| if(IKabs(x412)==0){ |
| continue; |
| } |
| IkReal gconst18=(x409*(pow(x412,-0.5))); |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x413=((-1.0)*new_r10); |
| CheckValue<IkReal> x415 = IKatan2WithCheck(IkReal(0),IkReal(x413),IKFAST_ATAN2_MAGTHRESH); |
| if(!x415.valid){ |
| continue; |
| } |
| IkReal x414=((-1.0)*(x415.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x414; |
| new_r00=0; |
| IkReal gconst16=x414; |
| IkReal gconst17=0; |
| IkReal x416 = new_r10*new_r10; |
| if(IKabs(x416)==0){ |
| continue; |
| } |
| IkReal gconst18=(x413*(pow(x416,-0.5))); |
| j0eval[0]=new_r10; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x417=IKPowWithIntegerCheck(gconst18,-1); |
| if(!x417.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x418=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x418.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*new_r11*(x417.value)), (gconst18*(x418.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x419=IKsin(j0); |
| IkReal x420=IKcos(j0); |
| IkReal x421=(gconst18*x419); |
| IkReal x422=((1.0)*x420); |
| evalcond[0]=(new_r10*x419); |
| evalcond[1]=x421; |
| evalcond[2]=(x421+new_r11); |
| evalcond[3]=(((gconst18*x420))+new_r01); |
| evalcond[4]=(gconst18+(((-1.0)*new_r10*x422))); |
| evalcond[5]=((((-1.0)*gconst18*x422))+new_r10); |
| evalcond[6]=((((-1.0)*new_r01*x419))+((new_r11*x420))); |
| evalcond[7]=(gconst18+((new_r11*x419))+((new_r01*x420))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x423=IKPowWithIntegerCheck(IKsign(gconst18),-1); |
| if(!x423.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x424 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x424.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x423.value)))+(x424.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x425=IKsin(j0); |
| IkReal x426=IKcos(j0); |
| IkReal x427=(gconst18*x425); |
| IkReal x428=((1.0)*x426); |
| evalcond[0]=(new_r10*x425); |
| evalcond[1]=x427; |
| evalcond[2]=(x427+new_r11); |
| evalcond[3]=(((gconst18*x426))+new_r01); |
| evalcond[4]=(gconst18+(((-1.0)*new_r10*x428))); |
| evalcond[5]=((((-1.0)*gconst18*x428))+new_r10); |
| evalcond[6]=((((-1.0)*new_r01*x425))+((new_r11*x426))); |
| evalcond[7]=(gconst18+((new_r11*x425))+((new_r01*x426))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x429=IKPowWithIntegerCheck(IKsign(gconst18),-1); |
| if(!x429.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x430 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x430.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x429.value)))+(x430.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x431=IKsin(j0); |
| IkReal x432=IKcos(j0); |
| IkReal x433=(gconst18*x431); |
| IkReal x434=((1.0)*x432); |
| evalcond[0]=(new_r10*x431); |
| evalcond[1]=x433; |
| evalcond[2]=(x433+new_r11); |
| evalcond[3]=(new_r01+((gconst18*x432))); |
| evalcond[4]=(gconst18+(((-1.0)*new_r10*x434))); |
| evalcond[5]=((((-1.0)*gconst18*x434))+new_r10); |
| evalcond[6]=(((new_r11*x432))+(((-1.0)*new_r01*x431))); |
| evalcond[7]=(((new_r01*x432))+gconst18+((new_r11*x431))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x436 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x436.valid){ |
| continue; |
| } |
| IkReal x435=((-1.0)*(x436.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x435; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst16=x435; |
| IkReal x437 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x437)==0){ |
| continue; |
| } |
| IkReal gconst17=((-1.0)*new_r00*(pow(x437,-0.5))); |
| IkReal gconst18=0; |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| CheckValue<IkReal> x439 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x439.valid){ |
| continue; |
| } |
| IkReal x438=((-1.0)*(x439.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x438; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst16=x438; |
| IkReal x440 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x440)==0){ |
| continue; |
| } |
| IkReal gconst17=((-1.0)*new_r00*(pow(x440,-0.5))); |
| IkReal gconst18=0; |
| j0eval[0]=new_r01; |
| j0eval[1]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x442 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x442.valid){ |
| continue; |
| } |
| IkReal x441=((-1.0)*(x442.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst17; |
| cj2=gconst18; |
| j2=x441; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst16=x441; |
| IkReal x443 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x443)==0){ |
| continue; |
| } |
| IkReal gconst17=((-1.0)*new_r00*(pow(x443,-0.5))); |
| IkReal gconst18=0; |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x444=IKPowWithIntegerCheck(gconst17,-1); |
| if(!x444.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x445=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x445.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((new_r01*(x444.value)), ((-1.0)*gconst17*(x445.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x446=IKcos(j0); |
| IkReal x447=IKsin(j0); |
| IkReal x448=(gconst17*x446); |
| IkReal x449=((1.0)*x447); |
| evalcond[0]=(new_r00*x447); |
| evalcond[1]=(new_r01*x446); |
| evalcond[2]=x448; |
| evalcond[3]=(gconst17*x447); |
| evalcond[4]=(((new_r00*x446))+gconst17); |
| evalcond[5]=(x448+new_r00); |
| evalcond[6]=((((-1.0)*new_r01*x449))+gconst17); |
| evalcond[7]=((((-1.0)*gconst17*x449))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x450=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x450.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x451=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x451.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((gconst17*(x450.value)), ((-1.0)*gconst17*(x451.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x452=IKcos(j0); |
| IkReal x453=IKsin(j0); |
| IkReal x454=(gconst17*x452); |
| IkReal x455=((1.0)*x453); |
| evalcond[0]=(new_r00*x453); |
| evalcond[1]=(new_r01*x452); |
| evalcond[2]=x454; |
| evalcond[3]=(gconst17*x453); |
| evalcond[4]=(((new_r00*x452))+gconst17); |
| evalcond[5]=(x454+new_r00); |
| evalcond[6]=((((-1.0)*new_r01*x455))+gconst17); |
| evalcond[7]=((((-1.0)*gconst17*x455))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x456=IKPowWithIntegerCheck(IKsign(gconst17),-1); |
| if(!x456.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x457 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x457.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x456.value)))+(x457.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x458=IKcos(j0); |
| IkReal x459=IKsin(j0); |
| IkReal x460=(gconst17*x458); |
| IkReal x461=((1.0)*x459); |
| evalcond[0]=(new_r00*x459); |
| evalcond[1]=(new_r01*x458); |
| evalcond[2]=x460; |
| evalcond[3]=(gconst17*x459); |
| evalcond[4]=(((new_r00*x458))+gconst17); |
| evalcond[5]=(x460+new_r00); |
| evalcond[6]=(gconst17+(((-1.0)*new_r01*x461))); |
| evalcond[7]=((((-1.0)*gconst17*x461))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x462=((1.0)*gconst17); |
| CheckValue<IkReal> x463=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| if(!x463.valid){ |
| continue; |
| } |
| 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); |
| if(!x464.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x463.value)))+(x464.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x465=IKsin(j0); |
| IkReal x466=IKcos(j0); |
| IkReal x467=(gconst17*x466); |
| IkReal x468=(gconst18*x465); |
| IkReal x469=(gconst17*x465); |
| IkReal x470=((1.0)*x466); |
| IkReal x471=(x468+x467); |
| evalcond[0]=(((new_r10*x465))+((new_r00*x466))+gconst17); |
| evalcond[1]=(((new_r11*x465))+((new_r01*x466))+gconst18); |
| evalcond[2]=(x471+new_r00); |
| evalcond[3]=(x471+new_r11); |
| evalcond[4]=(((new_r11*x466))+gconst17+(((-1.0)*new_r01*x465))); |
| evalcond[5]=(((new_r00*x465))+gconst18+(((-1.0)*new_r10*x470))); |
| evalcond[6]=((((-1.0)*x469))+((gconst18*x466))+new_r01); |
| evalcond[7]=((((-1.0)*gconst18*x470))+x469+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x472=((1.0)*gconst18); |
| 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); |
| if(!x473.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x474=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r01*x472))+((gconst17*new_r11)))),-1); |
| if(!x474.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x473.value)+(((1.5707963267949)*(x474.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x475=IKsin(j0); |
| IkReal x476=IKcos(j0); |
| IkReal x477=(gconst17*x476); |
| IkReal x478=(gconst18*x475); |
| IkReal x479=(gconst17*x475); |
| IkReal x480=((1.0)*x476); |
| IkReal x481=(x477+x478); |
| evalcond[0]=(((new_r10*x475))+gconst17+((new_r00*x476))); |
| evalcond[1]=(((new_r01*x476))+gconst18+((new_r11*x475))); |
| evalcond[2]=(x481+new_r00); |
| evalcond[3]=(x481+new_r11); |
| evalcond[4]=(gconst17+((new_r11*x476))+(((-1.0)*new_r01*x475))); |
| evalcond[5]=((((-1.0)*new_r10*x480))+gconst18+((new_r00*x475))); |
| evalcond[6]=((((-1.0)*x479))+((gconst18*x476))+new_r01); |
| evalcond[7]=(x479+(((-1.0)*gconst18*x480))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x482=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| if(!x482.valid){ |
| continue; |
| } |
| 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); |
| if(!x483.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x482.value)))+(x483.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x484=IKsin(j0); |
| IkReal x485=IKcos(j0); |
| IkReal x486=(gconst17*x485); |
| IkReal x487=(gconst18*x484); |
| IkReal x488=(gconst17*x484); |
| IkReal x489=((1.0)*x485); |
| IkReal x490=(x487+x486); |
| evalcond[0]=(gconst17+((new_r10*x484))+((new_r00*x485))); |
| evalcond[1]=(((new_r11*x484))+gconst18+((new_r01*x485))); |
| evalcond[2]=(x490+new_r00); |
| evalcond[3]=(x490+new_r11); |
| evalcond[4]=((((-1.0)*new_r01*x484))+((new_r11*x485))+gconst17); |
| evalcond[5]=((((-1.0)*new_r10*x489))+gconst18+((new_r00*x484))); |
| evalcond[6]=((((-1.0)*x488))+new_r01+((gconst18*x485))); |
| evalcond[7]=(x488+(((-1.0)*gconst18*x489))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| IkReal x493 = ((new_r10*new_r10)+(new_r00*new_r00)); |
| if(IKabs(x493)==0){ |
| continue; |
| } |
| IkReal x491=pow(x493,-0.5); |
| IkReal x492=((1.0)*x491); |
| CheckValue<IkReal> x494 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x494.valid){ |
| continue; |
| } |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*(x494.value)))); |
| IkReal gconst20=(new_r00*x492); |
| IkReal gconst21=(new_r10*x492); |
| CheckValue<IkReal> x495 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x495.valid){ |
| continue; |
| } |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x495.value)+j2)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x499 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x499.valid){ |
| continue; |
| } |
| IkReal x496=((1.0)*(x499.value)); |
| IkReal x497=x491; |
| IkReal x498=((1.0)*x497); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x496))); |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x496))); |
| IkReal gconst20=(new_r00*x498); |
| IkReal gconst21=(new_r10*x498); |
| IkReal x500=new_r10*new_r10; |
| IkReal x501=((1.0)*new_r10); |
| IkReal x502=(new_r00*new_r11); |
| IkReal x503=((((-1.0)*new_r01*x501))+x502); |
| IkReal x504=x491; |
| IkReal x505=(new_r00*x504); |
| j0eval[0]=x503; |
| j0eval[1]=IKsign(x503); |
| j0eval[2]=((IKabs((((x500*x504))+(((-1.0)*x502*x504)))))+(IKabs(((((-1.0)*x501*x505))+((new_r01*x505)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x509 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x509.valid){ |
| continue; |
| } |
| IkReal x506=((1.0)*(x509.value)); |
| IkReal x507=x491; |
| IkReal x508=((1.0)*x507); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x506))); |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x506))); |
| IkReal gconst20=(new_r00*x508); |
| IkReal gconst21=(new_r10*x508); |
| IkReal x510=new_r10*new_r10; |
| IkReal x511=new_r00*new_r00*new_r00; |
| CheckValue<IkReal> x515=IKPowWithIntegerCheck((x510+(new_r00*new_r00)),-1); |
| if(!x515.valid){ |
| continue; |
| } |
| IkReal x512=x515.value; |
| IkReal x513=((1.0)*x512); |
| IkReal x514=(x510*x512); |
| 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)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x519 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x519.valid){ |
| continue; |
| } |
| IkReal x516=((1.0)*(x519.value)); |
| IkReal x517=x491; |
| IkReal x518=((1.0)*x517); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x516))); |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x516))); |
| IkReal gconst20=(new_r00*x518); |
| IkReal gconst21=(new_r10*x518); |
| IkReal x520=new_r00*new_r00; |
| IkReal x521=(new_r00*new_r01); |
| IkReal x522=(((new_r10*new_r11))+x521); |
| IkReal x523=x491; |
| IkReal x524=((1.0)*x523); |
| j0eval[0]=x522; |
| j0eval[1]=((IKabs(((((-1.0)*new_r00*new_r11*x524))+((x520*x523)))))+(IKabs(((((-1.0)*x521*x524))+(((-1.0)*new_r00*new_r10*x524)))))); |
| j0eval[2]=IKsign(x522); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[3]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x526 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x526.valid){ |
| continue; |
| } |
| IkReal x525=((1.0)*(x526.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x525))); |
| new_r11=0; |
| new_r00=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x525))); |
| IkReal gconst20=0; |
| IkReal x527 = new_r10*new_r10; |
| if(IKabs(x527)==0){ |
| continue; |
| } |
| IkReal gconst21=((1.0)*new_r10*(pow(x527,-0.5))); |
| j0eval[0]=new_r10; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x528=IKPowWithIntegerCheck(gconst21,-1); |
| if(!x528.valid){ |
| continue; |
| } |
| cj0array[0]=(new_r10*(x528.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x529=IKsin(j0); |
| IkReal x530=IKcos(j0); |
| evalcond[0]=(new_r10*x529); |
| evalcond[1]=(gconst21*x529); |
| evalcond[2]=((-1.0)*new_r01*x529); |
| evalcond[3]=(((new_r01*x530))+gconst21); |
| evalcond[4]=(new_r01+((gconst21*x530))); |
| evalcond[5]=(gconst21+(((-1.0)*new_r10*x530))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x531=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x531.valid){ |
| continue; |
| } |
| cj0array[0]=(gconst21*(x531.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x532=IKsin(j0); |
| IkReal x533=IKcos(j0); |
| IkReal x534=(gconst21*x533); |
| evalcond[0]=(new_r10*x532); |
| evalcond[1]=(gconst21*x532); |
| evalcond[2]=((-1.0)*new_r01*x532); |
| evalcond[3]=(((new_r01*x533))+gconst21); |
| evalcond[4]=(x534+new_r01); |
| evalcond[5]=((((-1.0)*x534))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| evalcond[1]=gconst20; |
| evalcond[2]=gconst21; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x536 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x536.valid){ |
| continue; |
| } |
| IkReal x535=((1.0)*(x536.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x535))); |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x535))); |
| IkReal gconst20=((1.0)*new_r00); |
| IkReal gconst21=((1.0)*new_r10); |
| j0eval[0]=-1.0; |
| j0eval[1]=-1.0; |
| j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[4]; |
| CheckValue<IkReal> x538 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x538.valid){ |
| continue; |
| } |
| IkReal x537=((1.0)*(x538.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x537))); |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x537))); |
| IkReal gconst20=((1.0)*new_r00); |
| IkReal gconst21=((1.0)*new_r10); |
| j0eval[0]=-1.0; |
| j0eval[1]=-1.0; |
| j0eval[2]=new_r10; |
| j0eval[3]=1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x540 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x540.valid){ |
| continue; |
| } |
| IkReal x539=((1.0)*(x540.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x539))); |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x539))); |
| IkReal gconst20=((1.0)*new_r00); |
| IkReal gconst21=((1.0)*new_r10); |
| j0eval[0]=-1.0; |
| j0eval[1]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10)))); |
| j0eval[2]=-1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x541 = IKatan2WithCheck(IkReal((gconst21*new_r00)),IkReal((gconst20*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x541.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x542=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst20*gconst20)))+(((-1.0)*(gconst21*gconst21))))),-1); |
| if(!x542.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x541.value)+(((1.5707963267949)*(x542.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x543=IKcos(j0); |
| IkReal x544=IKsin(j0); |
| IkReal x545=(gconst21*x544); |
| IkReal x546=(gconst20*x543); |
| IkReal x547=((1.0)*x543); |
| IkReal x548=(gconst20*x544); |
| IkReal x549=(x545+x546); |
| evalcond[0]=x549; |
| evalcond[1]=(((new_r00*x543))+((new_r10*x544))+gconst20); |
| evalcond[2]=(x549+new_r00); |
| evalcond[3]=((((-1.0)*x548))+((gconst21*x543))); |
| evalcond[4]=(((new_r00*x544))+gconst21+(((-1.0)*new_r10*x547))); |
| evalcond[5]=(x548+new_r10+(((-1.0)*gconst21*x547))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x550 = IKatan2WithCheck(IkReal((gconst20*gconst21)),IkReal(((-1.0)*(gconst21*gconst21))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x550.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x551=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst21*new_r10))+(((-1.0)*gconst20*new_r00)))),-1); |
| if(!x551.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x550.value)+(((1.5707963267949)*(x551.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x552=IKcos(j0); |
| IkReal x553=IKsin(j0); |
| IkReal x554=(gconst21*x553); |
| IkReal x555=(gconst20*x552); |
| IkReal x556=((1.0)*x552); |
| IkReal x557=(gconst20*x553); |
| IkReal x558=(x555+x554); |
| evalcond[0]=x558; |
| evalcond[1]=(((new_r10*x553))+gconst20+((new_r00*x552))); |
| evalcond[2]=(x558+new_r00); |
| evalcond[3]=((((-1.0)*x557))+((gconst21*x552))); |
| evalcond[4]=(gconst21+(((-1.0)*new_r10*x556))+((new_r00*x553))); |
| evalcond[5]=(x557+(((-1.0)*gconst21*x556))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x559 = IKatan2WithCheck(IkReal((gconst20*gconst21)),IkReal(gconst20*gconst20),IKFAST_ATAN2_MAGTHRESH); |
| if(!x559.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x560=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst21*new_r10))+(((-1.0)*gconst20*new_r00)))),-1); |
| if(!x560.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x559.value)+(((1.5707963267949)*(x560.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x561=IKcos(j0); |
| IkReal x562=IKsin(j0); |
| IkReal x563=(gconst21*x562); |
| IkReal x564=(gconst20*x561); |
| IkReal x565=((1.0)*x561); |
| IkReal x566=(gconst20*x562); |
| IkReal x567=(x564+x563); |
| evalcond[0]=x567; |
| evalcond[1]=(((new_r00*x561))+gconst20+((new_r10*x562))); |
| evalcond[2]=(x567+new_r00); |
| evalcond[3]=(((gconst21*x561))+(((-1.0)*x566))); |
| evalcond[4]=(((new_r00*x562))+gconst21+(((-1.0)*new_r10*x565))); |
| evalcond[5]=((((-1.0)*gconst21*x565))+x566+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x569 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x569.valid){ |
| continue; |
| } |
| IkReal x568=((1.0)*(x569.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x568))); |
| new_r01=0; |
| new_r10=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x568))); |
| IkReal x570 = new_r00*new_r00; |
| if(IKabs(x570)==0){ |
| continue; |
| } |
| IkReal gconst20=((1.0)*new_r00*(pow(x570,-0.5))); |
| IkReal gconst21=0; |
| j0eval[0]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x572 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x572.valid){ |
| continue; |
| } |
| IkReal x571=((1.0)*(x572.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x571))); |
| new_r01=0; |
| new_r10=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x571))); |
| IkReal x573 = new_r00*new_r00; |
| if(IKabs(x573)==0){ |
| continue; |
| } |
| IkReal gconst20=((1.0)*new_r00*(pow(x573,-0.5))); |
| IkReal gconst21=0; |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x574=IKPowWithIntegerCheck(gconst20,-1); |
| if(!x574.valid){ |
| continue; |
| } |
| cj0array[0]=((-1.0)*new_r00*(x574.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x575=IKsin(j0); |
| IkReal x576=IKcos(j0); |
| evalcond[0]=(new_r00*x575); |
| evalcond[1]=(new_r11*x575); |
| evalcond[2]=((-1.0)*gconst20*x575); |
| evalcond[3]=(((new_r11*x576))+gconst20); |
| evalcond[4]=(((new_r00*x576))+gconst20); |
| evalcond[5]=(((gconst20*x576))+new_r11); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x577=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x577.valid){ |
| continue; |
| } |
| cj0array[0]=((-1.0)*gconst20*(x577.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x578=IKsin(j0); |
| IkReal x579=IKcos(j0); |
| IkReal x580=(gconst20*x579); |
| evalcond[0]=(new_r00*x578); |
| evalcond[1]=(new_r11*x578); |
| evalcond[2]=((-1.0)*gconst20*x578); |
| evalcond[3]=(((new_r11*x579))+gconst20); |
| evalcond[4]=(x580+new_r00); |
| evalcond[5]=(x580+new_r11); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x581=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x581.valid){ |
| continue; |
| } |
| cj0array[0]=((-1.0)*gconst20*(x581.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x582=IKsin(j0); |
| IkReal x583=IKcos(j0); |
| IkReal x584=(gconst20*x583); |
| evalcond[0]=(new_r00*x582); |
| evalcond[1]=(new_r11*x582); |
| evalcond[2]=((-1.0)*gconst20*x582); |
| evalcond[3]=(gconst20+((new_r00*x583))); |
| evalcond[4]=(x584+new_r00); |
| evalcond[5]=(x584+new_r11); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=IKabs(new_r00); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x586 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x586.valid){ |
| continue; |
| } |
| IkReal x585=((1.0)*(x586.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x585))); |
| new_r00=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x585))); |
| IkReal gconst20=0; |
| IkReal x587 = new_r10*new_r10; |
| if(IKabs(x587)==0){ |
| continue; |
| } |
| IkReal gconst21=((1.0)*new_r10*(pow(x587,-0.5))); |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x589 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x589.valid){ |
| continue; |
| } |
| IkReal x588=((1.0)*(x589.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x588))); |
| new_r00=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x588))); |
| IkReal gconst20=0; |
| IkReal x590 = new_r10*new_r10; |
| if(IKabs(x590)==0){ |
| continue; |
| } |
| IkReal gconst21=((1.0)*new_r10*(pow(x590,-0.5))); |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x592 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x592.valid){ |
| continue; |
| } |
| IkReal x591=((1.0)*(x592.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x591))); |
| new_r00=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x591))); |
| IkReal gconst20=0; |
| IkReal x593 = new_r10*new_r10; |
| if(IKabs(x593)==0){ |
| continue; |
| } |
| IkReal gconst21=((1.0)*new_r10*(pow(x593,-0.5))); |
| j0eval[0]=new_r10; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x594=IKPowWithIntegerCheck(gconst21,-1); |
| if(!x594.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x595=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x595.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*new_r11*(x594.value)), (gconst21*(x595.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x596=IKsin(j0); |
| IkReal x597=IKcos(j0); |
| IkReal x598=(gconst21*x596); |
| IkReal x599=((1.0)*x597); |
| evalcond[0]=(new_r10*x596); |
| evalcond[1]=x598; |
| evalcond[2]=(x598+new_r11); |
| evalcond[3]=(((gconst21*x597))+new_r01); |
| evalcond[4]=((((-1.0)*new_r10*x599))+gconst21); |
| evalcond[5]=((((-1.0)*gconst21*x599))+new_r10); |
| evalcond[6]=(((new_r11*x597))+(((-1.0)*new_r01*x596))); |
| evalcond[7]=(((new_r11*x596))+gconst21+((new_r01*x597))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x600=IKPowWithIntegerCheck(IKsign(gconst21),-1); |
| if(!x600.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x601 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x601.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x600.value)))+(x601.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x602=IKsin(j0); |
| IkReal x603=IKcos(j0); |
| IkReal x604=(gconst21*x602); |
| IkReal x605=((1.0)*x603); |
| evalcond[0]=(new_r10*x602); |
| evalcond[1]=x604; |
| evalcond[2]=(x604+new_r11); |
| evalcond[3]=(((gconst21*x603))+new_r01); |
| evalcond[4]=((((-1.0)*new_r10*x605))+gconst21); |
| evalcond[5]=(new_r10+(((-1.0)*gconst21*x605))); |
| evalcond[6]=(((new_r11*x603))+(((-1.0)*new_r01*x602))); |
| evalcond[7]=(gconst21+((new_r11*x602))+((new_r01*x603))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x606=IKPowWithIntegerCheck(IKsign(gconst21),-1); |
| if(!x606.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x607 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x607.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x606.value)))+(x607.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x608=IKsin(j0); |
| IkReal x609=IKcos(j0); |
| IkReal x610=(gconst21*x608); |
| IkReal x611=((1.0)*x609); |
| evalcond[0]=(new_r10*x608); |
| evalcond[1]=x610; |
| evalcond[2]=(x610+new_r11); |
| evalcond[3]=(((gconst21*x609))+new_r01); |
| evalcond[4]=(gconst21+(((-1.0)*new_r10*x611))); |
| evalcond[5]=((((-1.0)*gconst21*x611))+new_r10); |
| evalcond[6]=(((new_r11*x609))+(((-1.0)*new_r01*x608))); |
| evalcond[7]=(gconst21+((new_r11*x608))+((new_r01*x609))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x613 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x613.valid){ |
| continue; |
| } |
| IkReal x612=((1.0)*(x613.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x612))); |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x612))); |
| IkReal x614 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x614)==0){ |
| continue; |
| } |
| IkReal gconst20=((1.0)*new_r00*(pow(x614,-0.5))); |
| IkReal gconst21=0; |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| CheckValue<IkReal> x616 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x616.valid){ |
| continue; |
| } |
| IkReal x615=((1.0)*(x616.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x615))); |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x615))); |
| IkReal x617 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x617)==0){ |
| continue; |
| } |
| IkReal gconst20=((1.0)*new_r00*(pow(x617,-0.5))); |
| IkReal gconst21=0; |
| j0eval[0]=new_r01; |
| j0eval[1]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x619 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x619.valid){ |
| continue; |
| } |
| IkReal x618=((1.0)*(x619.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst20; |
| cj2=gconst21; |
| j2=((3.14159265)+(((-1.0)*x618))); |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst19=((3.14159265358979)+(((-1.0)*x618))); |
| IkReal x620 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x620)==0){ |
| continue; |
| } |
| IkReal gconst20=((1.0)*new_r00*(pow(x620,-0.5))); |
| IkReal gconst21=0; |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x621=IKPowWithIntegerCheck(gconst20,-1); |
| if(!x621.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x622=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x622.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((new_r01*(x621.value)), ((-1.0)*gconst20*(x622.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x623=IKcos(j0); |
| IkReal x624=IKsin(j0); |
| IkReal x625=(gconst20*x623); |
| IkReal x626=((1.0)*x624); |
| evalcond[0]=(new_r00*x624); |
| evalcond[1]=(new_r01*x623); |
| evalcond[2]=x625; |
| evalcond[3]=(gconst20*x624); |
| evalcond[4]=(gconst20+((new_r00*x623))); |
| evalcond[5]=(x625+new_r00); |
| evalcond[6]=((((-1.0)*new_r01*x626))+gconst20); |
| evalcond[7]=(new_r01+(((-1.0)*gconst20*x626))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x627=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x627.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x628=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x628.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((gconst20*(x627.value)), ((-1.0)*gconst20*(x628.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x629=IKcos(j0); |
| IkReal x630=IKsin(j0); |
| IkReal x631=(gconst20*x629); |
| IkReal x632=((1.0)*x630); |
| evalcond[0]=(new_r00*x630); |
| evalcond[1]=(new_r01*x629); |
| evalcond[2]=x631; |
| evalcond[3]=(gconst20*x630); |
| evalcond[4]=(gconst20+((new_r00*x629))); |
| evalcond[5]=(x631+new_r00); |
| evalcond[6]=((((-1.0)*new_r01*x632))+gconst20); |
| evalcond[7]=((((-1.0)*gconst20*x632))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x633 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x633.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x634=IKPowWithIntegerCheck(IKsign(gconst20),-1); |
| if(!x634.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x633.value)+(((1.5707963267949)*(x634.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x635=IKcos(j0); |
| IkReal x636=IKsin(j0); |
| IkReal x637=(gconst20*x635); |
| IkReal x638=((1.0)*x636); |
| evalcond[0]=(new_r00*x636); |
| evalcond[1]=(new_r01*x635); |
| evalcond[2]=x637; |
| evalcond[3]=(gconst20*x636); |
| evalcond[4]=(gconst20+((new_r00*x635))); |
| evalcond[5]=(x637+new_r00); |
| evalcond[6]=((((-1.0)*new_r01*x638))+gconst20); |
| evalcond[7]=((((-1.0)*gconst20*x638))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x639=((1.0)*gconst20); |
| CheckValue<IkReal> x640=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| if(!x640.valid){ |
| continue; |
| } |
| 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); |
| if(!x641.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x640.value)))+(x641.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x642=IKsin(j0); |
| IkReal x643=IKcos(j0); |
| IkReal x644=(gconst21*x642); |
| IkReal x645=(gconst20*x643); |
| IkReal x646=((1.0)*x643); |
| IkReal x647=(gconst20*x642); |
| IkReal x648=(x645+x644); |
| evalcond[0]=(gconst20+((new_r10*x642))+((new_r00*x643))); |
| evalcond[1]=(gconst21+((new_r11*x642))+((new_r01*x643))); |
| evalcond[2]=(x648+new_r00); |
| evalcond[3]=(x648+new_r11); |
| evalcond[4]=((((-1.0)*new_r01*x642))+gconst20+((new_r11*x643))); |
| evalcond[5]=(gconst21+(((-1.0)*new_r10*x646))+((new_r00*x642))); |
| evalcond[6]=((((-1.0)*x647))+((gconst21*x643))+new_r01); |
| evalcond[7]=((((-1.0)*gconst21*x646))+x647+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x649=((1.0)*gconst21); |
| 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); |
| if(!x650.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x651=IKPowWithIntegerCheck(IKsign((((gconst20*new_r11))+(((-1.0)*new_r01*x649)))),-1); |
| if(!x651.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x650.value)+(((1.5707963267949)*(x651.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x652=IKsin(j0); |
| IkReal x653=IKcos(j0); |
| IkReal x654=(gconst21*x652); |
| IkReal x655=(gconst20*x653); |
| IkReal x656=((1.0)*x653); |
| IkReal x657=(gconst20*x652); |
| IkReal x658=(x654+x655); |
| evalcond[0]=(gconst20+((new_r10*x652))+((new_r00*x653))); |
| evalcond[1]=(gconst21+((new_r01*x653))+((new_r11*x652))); |
| evalcond[2]=(x658+new_r00); |
| evalcond[3]=(x658+new_r11); |
| evalcond[4]=(gconst20+(((-1.0)*new_r01*x652))+((new_r11*x653))); |
| evalcond[5]=(gconst21+(((-1.0)*new_r10*x656))+((new_r00*x652))); |
| evalcond[6]=((((-1.0)*x657))+((gconst21*x653))+new_r01); |
| evalcond[7]=((((-1.0)*gconst21*x656))+x657+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| 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); |
| if(!x659.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x660=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| if(!x660.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x659.value)+(((1.5707963267949)*(x660.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x661=IKsin(j0); |
| IkReal x662=IKcos(j0); |
| IkReal x663=(gconst21*x661); |
| IkReal x664=(gconst20*x662); |
| IkReal x665=((1.0)*x662); |
| IkReal x666=(gconst20*x661); |
| IkReal x667=(x663+x664); |
| evalcond[0]=(gconst20+((new_r10*x661))+((new_r00*x662))); |
| evalcond[1]=(gconst21+((new_r11*x661))+((new_r01*x662))); |
| evalcond[2]=(x667+new_r00); |
| evalcond[3]=(x667+new_r11); |
| evalcond[4]=(gconst20+((new_r11*x662))+(((-1.0)*new_r01*x661))); |
| evalcond[5]=(gconst21+(((-1.0)*new_r10*x665))+((new_r00*x661))); |
| evalcond[6]=((((-1.0)*x666))+((gconst21*x662))+new_r01); |
| evalcond[7]=((((-1.0)*gconst21*x665))+x666+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| IkReal x668=((-1.0)*new_r11); |
| IkReal x670 = ((new_r01*new_r01)+(new_r11*new_r11)); |
| if(IKabs(x670)==0){ |
| continue; |
| } |
| IkReal x669=pow(x670,-0.5); |
| CheckValue<IkReal> x671 = IKatan2WithCheck(IkReal(new_r01),IkReal(x668),IKFAST_ATAN2_MAGTHRESH); |
| if(!x671.valid){ |
| continue; |
| } |
| IkReal gconst22=((-1.0)*(x671.value)); |
| IkReal gconst23=((-1.0)*new_r01*x669); |
| IkReal gconst24=(x668*x669); |
| CheckValue<IkReal> x672 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x672.valid){ |
| continue; |
| } |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x672.value)+j2)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| IkReal x673=((-1.0)*new_r11); |
| CheckValue<IkReal> x676 = IKatan2WithCheck(IkReal(new_r01),IkReal(x673),IKFAST_ATAN2_MAGTHRESH); |
| if(!x676.valid){ |
| continue; |
| } |
| IkReal x674=((-1.0)*(x676.value)); |
| IkReal x675=x669; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x674; |
| IkReal gconst22=x674; |
| IkReal gconst23=((-1.0)*new_r01*x675); |
| IkReal gconst24=(x673*x675); |
| IkReal x677=new_r01*new_r01; |
| IkReal x678=((1.0)*new_r10); |
| IkReal x679=((((-1.0)*new_r01*x678))+((new_r00*new_r11))); |
| IkReal x680=x669; |
| IkReal x681=(new_r11*x680); |
| j0eval[0]=x679; |
| j0eval[1]=IKsign(x679); |
| j0eval[2]=((IKabs(((((-1.0)*x678*x681))+((new_r01*x681)))))+(IKabs((((new_r00*x681))+(((-1.0)*x677*x680)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x682=((-1.0)*new_r11); |
| CheckValue<IkReal> x685 = IKatan2WithCheck(IkReal(new_r01),IkReal(x682),IKFAST_ATAN2_MAGTHRESH); |
| if(!x685.valid){ |
| continue; |
| } |
| IkReal x683=((-1.0)*(x685.value)); |
| IkReal x684=x669; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x683; |
| IkReal gconst22=x683; |
| IkReal gconst23=((-1.0)*new_r01*x684); |
| IkReal gconst24=(x682*x684); |
| IkReal x686=new_r01*new_r01; |
| IkReal x687=(((new_r10*new_r11))+((new_r00*new_r01))); |
| IkReal x688=x669; |
| IkReal x689=(new_r01*x688); |
| j0eval[0]=x687; |
| j0eval[1]=((IKabs(((((-1.0)*new_r00*x689))+((new_r11*x689)))))+(IKabs((((x686*x688))+((new_r10*x689)))))); |
| j0eval[2]=IKsign(x687); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x690=((-1.0)*new_r11); |
| CheckValue<IkReal> x693 = IKatan2WithCheck(IkReal(new_r01),IkReal(x690),IKFAST_ATAN2_MAGTHRESH); |
| if(!x693.valid){ |
| continue; |
| } |
| IkReal x691=((-1.0)*(x693.value)); |
| IkReal x692=x669; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x691; |
| IkReal gconst22=x691; |
| IkReal gconst23=((-1.0)*new_r01*x692); |
| IkReal gconst24=(x690*x692); |
| IkReal x694=new_r01*new_r01; |
| CheckValue<IkReal> x696=IKPowWithIntegerCheck(((new_r11*new_r11)+x694),-1); |
| if(!x696.valid){ |
| continue; |
| } |
| IkReal x695=x696.value; |
| j0eval[0]=((IKabs(((((-1.0)*x694*x695))+(new_r00*new_r00))))+(IKabs((((new_r01*new_r11*x695))+(((-1.0)*new_r00*new_r10)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[3]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| evalcond[1]=gconst24; |
| evalcond[2]=gconst23; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| IkReal x697=((-1.0)*new_r11); |
| CheckValue<IkReal> x699 = IKatan2WithCheck(IkReal(new_r01),IkReal(x697),IKFAST_ATAN2_MAGTHRESH); |
| if(!x699.valid){ |
| continue; |
| } |
| IkReal x698=((-1.0)*(x699.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x698; |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst22=x698; |
| IkReal gconst23=((-1.0)*new_r01); |
| IkReal gconst24=x697; |
| j0eval[0]=-1.0; |
| j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); |
| j0eval[2]=-1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x700=((-1.0)*new_r11); |
| CheckValue<IkReal> x702 = IKatan2WithCheck(IkReal(new_r01),IkReal(x700),IKFAST_ATAN2_MAGTHRESH); |
| if(!x702.valid){ |
| continue; |
| } |
| IkReal x701=((-1.0)*(x702.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x701; |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst22=x701; |
| IkReal gconst23=((-1.0)*new_r01); |
| IkReal gconst24=x700; |
| j0eval[0]=1.0; |
| j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); |
| j0eval[2]=1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x703=((-1.0)*new_r11); |
| CheckValue<IkReal> x705 = IKatan2WithCheck(IkReal(new_r01),IkReal(x703),IKFAST_ATAN2_MAGTHRESH); |
| if(!x705.valid){ |
| continue; |
| } |
| IkReal x704=((-1.0)*(x705.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x704; |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst22=x704; |
| IkReal gconst23=((-1.0)*new_r01); |
| IkReal gconst24=x703; |
| j0eval[0]=1.0; |
| j0eval[1]=1.0; |
| j0eval[2]=((IKabs((new_r01*new_r11)))+(IKabs(((1.0)+(((-1.0)*(new_r01*new_r01))))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x706 = IKatan2WithCheck(IkReal(gconst24*gconst24),IkReal((gconst23*gconst24)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x706.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x707=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst24*new_r11))+(((-1.0)*gconst23*new_r01)))),-1); |
| if(!x707.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x706.value)+(((1.5707963267949)*(x707.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x708=IKsin(j0); |
| IkReal x709=IKcos(j0); |
| IkReal x710=(gconst23*x709); |
| IkReal x711=(gconst24*x708); |
| IkReal x712=(gconst24*x709); |
| IkReal x713=((1.0)*x708); |
| IkReal x714=(x711+x710); |
| evalcond[0]=x714; |
| evalcond[1]=(((new_r01*x709))+gconst24+((new_r11*x708))); |
| evalcond[2]=(x714+new_r11); |
| evalcond[3]=((((-1.0)*x712))+((gconst23*x708))); |
| evalcond[4]=(gconst23+((new_r11*x709))+(((-1.0)*new_r01*x713))); |
| evalcond[5]=((((-1.0)*gconst23*x713))+x712+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x715=IKPowWithIntegerCheck(IKsign(((gconst23*gconst23)+(gconst24*gconst24))),-1); |
| if(!x715.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x716 = IKatan2WithCheck(IkReal((gconst23*new_r01)),IkReal(((-1.0)*gconst24*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x716.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x715.value)))+(x716.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x717=IKsin(j0); |
| IkReal x718=IKcos(j0); |
| IkReal x719=(gconst23*x718); |
| IkReal x720=(gconst24*x717); |
| IkReal x721=(gconst24*x718); |
| IkReal x722=((1.0)*x717); |
| IkReal x723=(x719+x720); |
| evalcond[0]=x723; |
| evalcond[1]=(((new_r01*x718))+gconst24+((new_r11*x717))); |
| evalcond[2]=(x723+new_r11); |
| evalcond[3]=((((-1.0)*x721))+((gconst23*x717))); |
| evalcond[4]=(gconst23+((new_r11*x718))+(((-1.0)*new_r01*x722))); |
| evalcond[5]=((((-1.0)*gconst23*x722))+x721+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x724 = IKatan2WithCheck(IkReal(gconst23*gconst23),IkReal(((-1.0)*gconst23*gconst24)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x724.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x725=IKPowWithIntegerCheck(IKsign((((gconst23*new_r01))+((gconst24*new_r11)))),-1); |
| if(!x725.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x724.value)+(((1.5707963267949)*(x725.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x726=IKsin(j0); |
| IkReal x727=IKcos(j0); |
| IkReal x728=(gconst23*x727); |
| IkReal x729=(gconst24*x726); |
| IkReal x730=(gconst24*x727); |
| IkReal x731=((1.0)*x726); |
| IkReal x732=(x728+x729); |
| evalcond[0]=x732; |
| evalcond[1]=(gconst24+((new_r01*x727))+((new_r11*x726))); |
| evalcond[2]=(x732+new_r11); |
| evalcond[3]=((((-1.0)*x730))+((gconst23*x726))); |
| evalcond[4]=(gconst23+(((-1.0)*new_r01*x731))+((new_r11*x727))); |
| evalcond[5]=((((-1.0)*gconst23*x731))+x730+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| IkReal x733=((-1.0)*new_r11); |
| CheckValue<IkReal> x735 = IKatan2WithCheck(IkReal(0),IkReal(x733),IKFAST_ATAN2_MAGTHRESH); |
| if(!x735.valid){ |
| continue; |
| } |
| IkReal x734=((-1.0)*(x735.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x734; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst22=x734; |
| IkReal gconst23=0; |
| IkReal x736 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x736)==0){ |
| continue; |
| } |
| IkReal gconst24=(x733*(pow(x736,-0.5))); |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| IkReal x737=((-1.0)*new_r11); |
| CheckValue<IkReal> x739 = IKatan2WithCheck(IkReal(0),IkReal(x737),IKFAST_ATAN2_MAGTHRESH); |
| if(!x739.valid){ |
| continue; |
| } |
| IkReal x738=((-1.0)*(x739.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x738; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst22=x738; |
| IkReal gconst23=0; |
| IkReal x740 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x740)==0){ |
| continue; |
| } |
| IkReal gconst24=(x737*(pow(x740,-0.5))); |
| j0eval[0]=new_r11; |
| j0eval[1]=new_r10; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x741=((-1.0)*new_r11); |
| CheckValue<IkReal> x743 = IKatan2WithCheck(IkReal(0),IkReal(x741),IKFAST_ATAN2_MAGTHRESH); |
| if(!x743.valid){ |
| continue; |
| } |
| IkReal x742=((-1.0)*(x743.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x742; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst22=x742; |
| IkReal gconst23=0; |
| IkReal x744 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x744)==0){ |
| continue; |
| } |
| IkReal gconst24=(x741*(pow(x744,-0.5))); |
| j0eval[0]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x745=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x745.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x746=IKPowWithIntegerCheck(gconst24,-1); |
| if(!x746.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst24*(x745.value)), (new_r10*(x746.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x747=IKsin(j0); |
| IkReal x748=IKcos(j0); |
| IkReal x749=(gconst24*x747); |
| IkReal x750=((1.0)*x748); |
| evalcond[0]=(new_r11*x748); |
| evalcond[1]=(new_r10*x747); |
| evalcond[2]=x749; |
| evalcond[3]=(gconst24*x748); |
| evalcond[4]=(gconst24+((new_r11*x747))); |
| evalcond[5]=(x749+new_r11); |
| evalcond[6]=(gconst24+(((-1.0)*new_r10*x750))); |
| evalcond[7]=((((-1.0)*gconst24*x750))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x751=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x751.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x752=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x752.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst24*(x751.value)), (gconst24*(x752.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x753=IKsin(j0); |
| IkReal x754=IKcos(j0); |
| IkReal x755=(gconst24*x753); |
| IkReal x756=((1.0)*x754); |
| evalcond[0]=(new_r11*x754); |
| evalcond[1]=(new_r10*x753); |
| evalcond[2]=x755; |
| evalcond[3]=(gconst24*x754); |
| evalcond[4]=(gconst24+((new_r11*x753))); |
| evalcond[5]=(x755+new_r11); |
| evalcond[6]=(gconst24+(((-1.0)*new_r10*x756))); |
| evalcond[7]=((((-1.0)*gconst24*x756))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x757=IKPowWithIntegerCheck(IKsign(gconst24),-1); |
| if(!x757.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x758 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x758.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x757.value)))+(x758.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x759=IKsin(j0); |
| IkReal x760=IKcos(j0); |
| IkReal x761=(gconst24*x759); |
| IkReal x762=((1.0)*x760); |
| evalcond[0]=(new_r11*x760); |
| evalcond[1]=(new_r10*x759); |
| evalcond[2]=x761; |
| evalcond[3]=(gconst24*x760); |
| evalcond[4]=(gconst24+((new_r11*x759))); |
| evalcond[5]=(x761+new_r11); |
| evalcond[6]=(gconst24+(((-1.0)*new_r10*x762))); |
| evalcond[7]=((((-1.0)*gconst24*x762))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x764 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x764.valid){ |
| continue; |
| } |
| IkReal x763=((-1.0)*(x764.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x763; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst22=x763; |
| IkReal x765 = new_r01*new_r01; |
| if(IKabs(x765)==0){ |
| continue; |
| } |
| IkReal gconst23=((-1.0)*new_r01*(pow(x765,-0.5))); |
| IkReal gconst24=0; |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| CheckValue<IkReal> x767 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x767.valid){ |
| continue; |
| } |
| IkReal x766=((-1.0)*(x767.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x766; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst22=x766; |
| IkReal x768 = new_r01*new_r01; |
| if(IKabs(x768)==0){ |
| continue; |
| } |
| IkReal gconst23=((-1.0)*new_r01*(pow(x768,-0.5))); |
| IkReal gconst24=0; |
| j0eval[0]=new_r01; |
| j0eval[1]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x770 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x770.valid){ |
| continue; |
| } |
| IkReal x769=((-1.0)*(x770.value)); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst23; |
| cj2=gconst24; |
| j2=x769; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst22=x769; |
| IkReal x771 = new_r01*new_r01; |
| if(IKabs(x771)==0){ |
| continue; |
| } |
| IkReal gconst23=((-1.0)*new_r01*(pow(x771,-0.5))); |
| IkReal gconst24=0; |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x772=IKPowWithIntegerCheck(gconst23,-1); |
| if(!x772.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x773=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x773.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((new_r01*(x772.value)), ((-1.0)*gconst23*(x773.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x774=IKcos(j0); |
| IkReal x775=IKsin(j0); |
| IkReal x776=(gconst23*x774); |
| IkReal x777=(gconst23*x775); |
| evalcond[0]=(new_r00*x775); |
| evalcond[1]=(new_r01*x774); |
| evalcond[2]=x776; |
| evalcond[3]=x777; |
| evalcond[4]=(gconst23+((new_r00*x774))); |
| evalcond[5]=(x776+new_r00); |
| evalcond[6]=(gconst23+(((-1.0)*new_r01*x775))); |
| evalcond[7]=(new_r01+(((-1.0)*x777))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x778=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x778.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x779=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x779.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((gconst23*(x778.value)), ((-1.0)*gconst23*(x779.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x780=IKcos(j0); |
| IkReal x781=IKsin(j0); |
| IkReal x782=(gconst23*x780); |
| IkReal x783=(gconst23*x781); |
| evalcond[0]=(new_r00*x781); |
| evalcond[1]=(new_r01*x780); |
| evalcond[2]=x782; |
| evalcond[3]=x783; |
| evalcond[4]=(gconst23+((new_r00*x780))); |
| evalcond[5]=(x782+new_r00); |
| evalcond[6]=(gconst23+(((-1.0)*new_r01*x781))); |
| evalcond[7]=((((-1.0)*x783))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x784 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x784.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x785=IKPowWithIntegerCheck(IKsign(gconst23),-1); |
| if(!x785.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x784.value)+(((1.5707963267949)*(x785.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x786=IKcos(j0); |
| IkReal x787=IKsin(j0); |
| IkReal x788=(gconst23*x786); |
| IkReal x789=(gconst23*x787); |
| evalcond[0]=(new_r00*x787); |
| evalcond[1]=(new_r01*x786); |
| evalcond[2]=x788; |
| evalcond[3]=x789; |
| evalcond[4]=(gconst23+((new_r00*x786))); |
| evalcond[5]=(x788+new_r00); |
| evalcond[6]=(gconst23+(((-1.0)*new_r01*x787))); |
| evalcond[7]=((((-1.0)*x789))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x790=((1.0)*new_r00); |
| CheckValue<IkReal> x791=IKPowWithIntegerCheck(IKsign((((gconst23*new_r10))+(((-1.0)*gconst24*x790)))),-1); |
| if(!x791.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x792 = IKatan2WithCheck(IkReal(((((-1.0)*(gconst23*gconst23)))+(new_r00*new_r00))),IkReal(((((-1.0)*new_r10*x790))+((gconst23*gconst24)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x792.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x791.value)))+(x792.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x793=IKsin(j0); |
| IkReal x794=IKcos(j0); |
| IkReal x795=(gconst23*x794); |
| IkReal x796=(gconst24*x793); |
| IkReal x797=((1.0)*x794); |
| IkReal x798=((1.0)*x793); |
| IkReal x799=(x795+x796); |
| evalcond[0]=(((new_r10*x793))+gconst23+((new_r00*x794))); |
| evalcond[1]=(((new_r11*x793))+gconst24+((new_r01*x794))); |
| evalcond[2]=(x799+new_r00); |
| evalcond[3]=(x799+new_r11); |
| evalcond[4]=((((-1.0)*new_r01*x798))+((new_r11*x794))+gconst23); |
| evalcond[5]=(gconst24+(((-1.0)*new_r10*x797))+((new_r00*x793))); |
| evalcond[6]=((((-1.0)*gconst23*x798))+((gconst24*x794))+new_r01); |
| evalcond[7]=((((-1.0)*gconst24*x797))+((gconst23*x793))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x800=((1.0)*gconst23); |
| 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); |
| if(!x801.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x802=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| if(!x802.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x801.value)+(((1.5707963267949)*(x802.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x803=IKsin(j0); |
| IkReal x804=IKcos(j0); |
| IkReal x805=(gconst23*x804); |
| IkReal x806=(gconst24*x803); |
| IkReal x807=((1.0)*x804); |
| IkReal x808=((1.0)*x803); |
| IkReal x809=(x805+x806); |
| evalcond[0]=(gconst23+((new_r00*x804))+((new_r10*x803))); |
| evalcond[1]=(gconst24+((new_r11*x803))+((new_r01*x804))); |
| evalcond[2]=(new_r00+x809); |
| evalcond[3]=(new_r11+x809); |
| evalcond[4]=((((-1.0)*new_r01*x808))+gconst23+((new_r11*x804))); |
| evalcond[5]=(gconst24+((new_r00*x803))+(((-1.0)*new_r10*x807))); |
| evalcond[6]=(new_r01+(((-1.0)*gconst23*x808))+((gconst24*x804))); |
| evalcond[7]=((((-1.0)*gconst24*x807))+((gconst23*x803))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| 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); |
| if(!x810.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x811=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| if(!x811.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x810.value)+(((1.5707963267949)*(x811.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x812=IKsin(j0); |
| IkReal x813=IKcos(j0); |
| IkReal x814=(gconst23*x813); |
| IkReal x815=(gconst24*x812); |
| IkReal x816=((1.0)*x813); |
| IkReal x817=((1.0)*x812); |
| IkReal x818=(x814+x815); |
| evalcond[0]=(((new_r00*x813))+((new_r10*x812))+gconst23); |
| evalcond[1]=(((new_r11*x812))+((new_r01*x813))+gconst24); |
| evalcond[2]=(new_r00+x818); |
| evalcond[3]=(new_r11+x818); |
| evalcond[4]=(((new_r11*x813))+gconst23+(((-1.0)*new_r01*x817))); |
| evalcond[5]=(((new_r00*x812))+gconst24+(((-1.0)*new_r10*x816))); |
| evalcond[6]=((((-1.0)*gconst23*x817))+((gconst24*x813))+new_r01); |
| evalcond[7]=(((gconst23*x812))+(((-1.0)*gconst24*x816))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| IkReal x821 = ((new_r01*new_r01)+(new_r11*new_r11)); |
| if(IKabs(x821)==0){ |
| continue; |
| } |
| IkReal x819=pow(x821,-0.5); |
| IkReal x820=((1.0)*x819); |
| CheckValue<IkReal> x822 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x822.valid){ |
| continue; |
| } |
| IkReal gconst25=((3.14159265358979)+(((-1.0)*(x822.value)))); |
| IkReal gconst26=(new_r01*x820); |
| IkReal gconst27=(new_r11*x820); |
| CheckValue<IkReal> x823 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x823.valid){ |
| continue; |
| } |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x823.value)+j2)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x827 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x827.valid){ |
| continue; |
| } |
| IkReal x824=((1.0)*(x827.value)); |
| IkReal x825=x819; |
| IkReal x826=((1.0)*x825); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst26; |
| cj2=gconst27; |
| j2=((3.14159265)+(((-1.0)*x824))); |
| IkReal gconst25=((3.14159265358979)+(((-1.0)*x824))); |
| IkReal gconst26=(new_r01*x826); |
| IkReal gconst27=(new_r11*x826); |
| IkReal x828=new_r01*new_r01; |
| IkReal x829=((1.0)*new_r01); |
| IkReal x830=((((-1.0)*new_r10*x829))+((new_r00*new_r11))); |
| IkReal x831=x819; |
| IkReal x832=(new_r11*x831); |
| j0eval[0]=x830; |
| j0eval[1]=((IKabs(((((-1.0)*new_r00*x832))+((x828*x831)))))+(IKabs(((((-1.0)*x829*x832))+((new_r10*x832)))))); |
| j0eval[2]=IKsign(x830); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x836 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x836.valid){ |
| continue; |
| } |
| IkReal x833=((1.0)*(x836.value)); |
| IkReal x834=x819; |
| IkReal x835=((1.0)*x834); |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| sj2=gconst26; |
| cj2=gconst27; |
| j2=((3.14159265)+(((-1.0)*x833))); |
| IkReal gconst25=((3.14159265358979)+(((-1.0)*x833))); |
| IkReal gconst26=(new_r01*x835); |
| IkReal gconst27=(new_r11*x835); |
| IkReal x837=new_r01*new_r01; |
| IkReal x838=(new_r00*new_r01); |
| IkReal x839=(((new_r10*new_r11))+x838); |
| IkReal x840=x819; |
| IkReal x841=((1.0)*new_r01*x840); |
| j0eval[0]=x839; |
| j0eval[1]=((IKabs((((x838*x840))+(((-1.0)*new_r11*x841)))))+(IKabs(((((-1.0)*new_r10*x841))+(((-1.0)*x837*x840)))))); |
| j0eval[2]=IKsign(x839); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x842=((1.0)*new_r00); |
| CheckValue<IkReal> x843 = IKatan2WithCheck(IkReal(((((-1.0)*(gconst26*gconst26)))+(new_r00*new_r00))),IkReal(((((-1.0)*new_r10*x842))+((gconst26*gconst27)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x843.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x844=IKPowWithIntegerCheck(IKsign((((gconst26*new_r10))+(((-1.0)*gconst27*x842)))),-1); |
| if(!x844.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x843.value)+(((1.5707963267949)*(x844.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x845=IKsin(j0); |
| IkReal x846=IKcos(j0); |
| IkReal x847=(gconst26*x846); |
| IkReal x848=(gconst27*x845); |
| IkReal x849=(gconst27*x846); |
| IkReal x850=(gconst26*x845); |
| IkReal x851=(x847+x848); |
| evalcond[0]=(((new_r10*x845))+((new_r00*x846))+gconst26); |
| evalcond[1]=(gconst27+((new_r01*x846))+((new_r11*x845))); |
| evalcond[2]=(new_r00+x851); |
| evalcond[3]=(new_r11+x851); |
| evalcond[4]=((((-1.0)*new_r01*x845))+gconst26+((new_r11*x846))); |
| evalcond[5]=(((new_r00*x845))+gconst27+(((-1.0)*new_r10*x846))); |
| evalcond[6]=((((-1.0)*x850))+new_r01+x849); |
| evalcond[7]=((((-1.0)*x849))+new_r10+x850); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x852=((1.0)*gconst26); |
| 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); |
| if(!x853.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x854=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| if(!x854.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x853.value)+(((1.5707963267949)*(x854.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x855=IKsin(j0); |
| IkReal x856=IKcos(j0); |
| IkReal x857=(gconst26*x856); |
| IkReal x858=(gconst27*x855); |
| IkReal x859=(gconst27*x856); |
| IkReal x860=(gconst26*x855); |
| IkReal x861=(x857+x858); |
| evalcond[0]=(gconst26+((new_r10*x855))+((new_r00*x856))); |
| evalcond[1]=(gconst27+((new_r11*x855))+((new_r01*x856))); |
| evalcond[2]=(new_r00+x861); |
| evalcond[3]=(new_r11+x861); |
| evalcond[4]=(gconst26+((new_r11*x856))+(((-1.0)*new_r01*x855))); |
| evalcond[5]=(gconst27+(((-1.0)*new_r10*x856))+((new_r00*x855))); |
| evalcond[6]=((((-1.0)*x860))+new_r01+x859); |
| evalcond[7]=((((-1.0)*x859))+new_r10+x860); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x862=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| if(!x862.valid){ |
| continue; |
| } |
| 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); |
| if(!x863.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x862.value)))+(x863.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x864=IKsin(j0); |
| IkReal x865=IKcos(j0); |
| IkReal x866=(gconst26*x865); |
| IkReal x867=(gconst27*x864); |
| IkReal x868=(gconst27*x865); |
| IkReal x869=(gconst26*x864); |
| IkReal x870=(x867+x866); |
| evalcond[0]=(((new_r00*x865))+gconst26+((new_r10*x864))); |
| evalcond[1]=(((new_r01*x865))+gconst27+((new_r11*x864))); |
| evalcond[2]=(new_r00+x870); |
| evalcond[3]=(new_r11+x870); |
| evalcond[4]=(gconst26+((new_r11*x865))+(((-1.0)*new_r01*x864))); |
| evalcond[5]=(((new_r00*x864))+(((-1.0)*new_r10*x865))+gconst27); |
| evalcond[6]=((((-1.0)*x869))+new_r01+x868); |
| evalcond[7]=((((-1.0)*x868))+new_r10+x869); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j0] |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x872 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x872.valid){ |
| continue; |
| } |
| IkReal x871=x872.value; |
| j0array[0]=((-1.0)*x871); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| j0array[1]=((3.14159265358979)+(((-1.0)*x871))); |
| sj0array[1]=IKsin(j0array[1]); |
| cj0array[1]=IKcos(j0array[1]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| if( j0array[1] > IKPI ) |
| { |
| j0array[1]-=IK2PI; |
| } |
| else if( j0array[1] < -IKPI ) |
| { j0array[1]+=IK2PI; |
| } |
| j0valid[1] = true; |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[1]; |
| evalcond[0]=(((new_r00*(IKsin(j0))))+(((-1.0)*new_r10*(IKcos(j0))))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| j0eval[0]=new_r01; |
| j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| j0eval[2]=IKsign(new_r01); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| j0eval[0]=new_r00; |
| j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| j0eval[2]=IKsign(new_r00); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| j0eval[0]=new_r01; |
| j0eval[1]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j0] |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x873=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x873.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x874=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x874.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((sj2*(x873.value)), ((-1.0)*sj2*(x874.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x875=IKcos(j0); |
| IkReal x876=IKsin(j0); |
| IkReal x877=(sj2*x875); |
| IkReal x878=(cj2*x876); |
| IkReal x879=(sj2*x876); |
| IkReal x880=(cj2*x875); |
| IkReal x881=(x878+x877); |
| evalcond[0]=(((new_r00*x876))+cj2); |
| evalcond[1]=(((new_r00*x875))+sj2); |
| evalcond[2]=(((new_r01*x875))+cj2); |
| evalcond[3]=(sj2+(((-1.0)*new_r01*x876))); |
| evalcond[4]=x881; |
| evalcond[5]=(new_r00+x881); |
| evalcond[6]=((((-1.0)*x880))+x879); |
| evalcond[7]=((((-1.0)*x879))+new_r01+x880); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x882 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x882.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x883=IKPowWithIntegerCheck(IKsign(new_r00),-1); |
| if(!x883.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x882.value)+(((1.5707963267949)*(x883.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x884=IKcos(j0); |
| IkReal x885=IKsin(j0); |
| IkReal x886=(sj2*x884); |
| IkReal x887=(cj2*x885); |
| IkReal x888=(sj2*x885); |
| IkReal x889=(cj2*x884); |
| IkReal x890=(x887+x886); |
| evalcond[0]=(cj2+((new_r00*x885))); |
| evalcond[1]=(sj2+((new_r00*x884))); |
| evalcond[2]=(cj2+((new_r01*x884))); |
| evalcond[3]=(sj2+(((-1.0)*new_r01*x885))); |
| evalcond[4]=x890; |
| evalcond[5]=(new_r00+x890); |
| evalcond[6]=((((-1.0)*x889))+x888); |
| evalcond[7]=((((-1.0)*x888))+new_r01+x889); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x891=IKPowWithIntegerCheck(IKsign(new_r01),-1); |
| if(!x891.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x892 = IKatan2WithCheck(IkReal(sj2),IkReal(((-1.0)*cj2)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x892.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x891.value)))+(x892.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x893=IKcos(j0); |
| IkReal x894=IKsin(j0); |
| IkReal x895=(sj2*x893); |
| IkReal x896=(cj2*x894); |
| IkReal x897=(sj2*x894); |
| IkReal x898=(cj2*x893); |
| IkReal x899=(x896+x895); |
| evalcond[0]=(cj2+((new_r00*x894))); |
| evalcond[1]=(sj2+((new_r00*x893))); |
| evalcond[2]=(cj2+((new_r01*x893))); |
| evalcond[3]=(sj2+(((-1.0)*new_r01*x894))); |
| evalcond[4]=x899; |
| evalcond[5]=(new_r00+x899); |
| evalcond[6]=((((-1.0)*x898))+x897); |
| evalcond[7]=((((-1.0)*x897))+new_r01+x898); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| j0eval[0]=new_r10; |
| j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| j0eval[2]=IKsign(new_r10); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| j0eval[0]=new_r11; |
| j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| j0eval[2]=IKsign(new_r11); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| j0eval[0]=new_r11; |
| j0eval[1]=new_r10; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j0] |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x900=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x900.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x901=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x901.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*cj2*(x900.value)), (cj2*(x901.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x902=IKsin(j0); |
| IkReal x903=IKcos(j0); |
| IkReal x904=(sj2*x903); |
| IkReal x905=(cj2*x902); |
| IkReal x906=(sj2*x902); |
| IkReal x907=((1.0)*x903); |
| IkReal x908=(x904+x905); |
| evalcond[0]=(sj2+((new_r11*x903))); |
| evalcond[1]=(sj2+((new_r10*x902))); |
| evalcond[2]=(cj2+((new_r11*x902))); |
| evalcond[3]=(cj2+(((-1.0)*new_r10*x907))); |
| evalcond[4]=x908; |
| evalcond[5]=(new_r11+x908); |
| evalcond[6]=(((cj2*x903))+(((-1.0)*x906))); |
| evalcond[7]=(new_r10+x906+(((-1.0)*cj2*x907))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x909=IKPowWithIntegerCheck(IKsign(new_r11),-1); |
| if(!x909.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x910 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x910.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x909.value)))+(x910.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x911=IKsin(j0); |
| IkReal x912=IKcos(j0); |
| IkReal x913=(sj2*x912); |
| IkReal x914=(cj2*x911); |
| IkReal x915=(sj2*x911); |
| IkReal x916=((1.0)*x912); |
| IkReal x917=(x913+x914); |
| evalcond[0]=(sj2+((new_r11*x912))); |
| evalcond[1]=(sj2+((new_r10*x911))); |
| evalcond[2]=(cj2+((new_r11*x911))); |
| evalcond[3]=(cj2+(((-1.0)*new_r10*x916))); |
| evalcond[4]=x917; |
| evalcond[5]=(new_r11+x917); |
| evalcond[6]=(((cj2*x912))+(((-1.0)*x915))); |
| evalcond[7]=(new_r10+x915+(((-1.0)*cj2*x916))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x918=IKPowWithIntegerCheck(IKsign(new_r10),-1); |
| if(!x918.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x919 = IKatan2WithCheck(IkReal(((-1.0)*sj2)),IkReal(cj2),IKFAST_ATAN2_MAGTHRESH); |
| if(!x919.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x918.value)))+(x919.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x920=IKsin(j0); |
| IkReal x921=IKcos(j0); |
| IkReal x922=(sj2*x921); |
| IkReal x923=(cj2*x920); |
| IkReal x924=(sj2*x920); |
| IkReal x925=((1.0)*x921); |
| IkReal x926=(x922+x923); |
| evalcond[0]=(sj2+((new_r11*x921))); |
| evalcond[1]=(sj2+((new_r10*x920))); |
| evalcond[2]=(cj2+((new_r11*x920))); |
| evalcond[3]=(cj2+(((-1.0)*new_r10*x925))); |
| evalcond[4]=x926; |
| evalcond[5]=(new_r11+x926); |
| evalcond[6]=((((-1.0)*x924))+((cj2*x921))); |
| evalcond[7]=((((-1.0)*cj2*x925))+new_r10+x924); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| sj1=1.0; |
| cj1=0; |
| j1=1.5707963267949; |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j0] |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x928 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); |
| if(!x928.valid){ |
| continue; |
| } |
| IkReal x927=x928.value; |
| j0array[0]=((-1.0)*x927); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| j0array[1]=((3.14159265358979)+(((-1.0)*x927))); |
| sj0array[1]=IKsin(j0array[1]); |
| cj0array[1]=IKcos(j0array[1]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| if( j0array[1] > IKPI ) |
| { |
| j0array[1]-=IK2PI; |
| } |
| else if( j0array[1] < -IKPI ) |
| { j0array[1]+=IK2PI; |
| } |
| j0valid[1] = true; |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[1]; |
| evalcond[0]=(((new_r11*(IKcos(j0))))+(((-1.0)*new_r01*(IKsin(j0))))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x929=((1.0)*sj2); |
| CheckValue<IkReal> x930=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x929))+((cj2*new_r00)))),-1); |
| if(!x930.valid){ |
| continue; |
| } |
| 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); |
| if(!x931.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x930.value)))+(x931.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x932=IKsin(j0); |
| IkReal x933=IKcos(j0); |
| IkReal x934=(sj2*x933); |
| IkReal x935=(cj2*x932); |
| IkReal x936=(sj2*x932); |
| IkReal x937=((1.0)*x933); |
| IkReal x938=(x935+x934); |
| evalcond[0]=(sj2+((new_r00*x933))+((new_r10*x932))); |
| evalcond[1]=(cj2+((new_r01*x933))+((new_r11*x932))); |
| evalcond[2]=(new_r00+x938); |
| evalcond[3]=(new_r11+x938); |
| evalcond[4]=(sj2+(((-1.0)*new_r01*x932))+((new_r11*x933))); |
| evalcond[5]=(cj2+(((-1.0)*new_r10*x937))+((new_r00*x932))); |
| evalcond[6]=(((cj2*x933))+(((-1.0)*x936))+new_r01); |
| evalcond[7]=((((-1.0)*cj2*x937))+new_r10+x936); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x939=IKPowWithIntegerCheck(IKsign((((cj2*new_r01))+(((-1.0)*new_r11*sj2)))),-1); |
| if(!x939.valid){ |
| continue; |
| } |
| 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); |
| if(!x940.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x939.value)))+(x940.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x941=IKsin(j0); |
| IkReal x942=IKcos(j0); |
| IkReal x943=(sj2*x942); |
| IkReal x944=(cj2*x941); |
| IkReal x945=(sj2*x941); |
| IkReal x946=((1.0)*x942); |
| IkReal x947=(x943+x944); |
| evalcond[0]=(sj2+((new_r00*x942))+((new_r10*x941))); |
| evalcond[1]=(cj2+((new_r01*x942))+((new_r11*x941))); |
| evalcond[2]=(new_r00+x947); |
| evalcond[3]=(new_r11+x947); |
| evalcond[4]=((((-1.0)*new_r01*x941))+sj2+((new_r11*x942))); |
| evalcond[5]=(((new_r00*x941))+cj2+(((-1.0)*new_r10*x946))); |
| evalcond[6]=(((cj2*x942))+(((-1.0)*x945))+new_r01); |
| evalcond[7]=((((-1.0)*cj2*x946))+new_r10+x945); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| 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); |
| if(!x948.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x949=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| if(!x949.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x948.value)+(((1.5707963267949)*(x949.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x950=IKsin(j0); |
| IkReal x951=IKcos(j0); |
| IkReal x952=(sj2*x951); |
| IkReal x953=(cj2*x950); |
| IkReal x954=(sj2*x950); |
| IkReal x955=((1.0)*x951); |
| IkReal x956=(x953+x952); |
| evalcond[0]=(((new_r10*x950))+((new_r00*x951))+sj2); |
| evalcond[1]=(((new_r01*x951))+cj2+((new_r11*x950))); |
| evalcond[2]=(new_r00+x956); |
| evalcond[3]=(new_r11+x956); |
| evalcond[4]=(sj2+(((-1.0)*new_r01*x950))+((new_r11*x951))); |
| evalcond[5]=(((new_r00*x950))+cj2+(((-1.0)*new_r10*x955))); |
| evalcond[6]=((((-1.0)*x954))+((cj2*x951))+new_r01); |
| evalcond[7]=((((-1.0)*cj2*x955))+new_r10+x954); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r02; |
| evalcond[2]=new_r12; |
| evalcond[3]=new_r20; |
| evalcond[4]=new_r21; |
| 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 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| IkReal x957=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11))); |
| j0eval[0]=x957; |
| j0eval[1]=IKsign(x957); |
| j0eval[2]=((IKabs((((new_r10*sj2))+((cj2*new_r11)))))+(IKabs((((new_r00*sj2))+((cj2*new_r01)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| IkReal x958=((1.0)*sj2); |
| IkReal x959=((((-1.0)*new_r01*x958))+((cj2*new_r11))); |
| j0eval[0]=x959; |
| j0eval[1]=((IKabs(((-1.0)+(cj2*cj2)+(new_r11*new_r11))))+(IKabs(((((-1.0)*cj2*x958))+((new_r01*new_r11)))))); |
| j0eval[2]=IKsign(x959); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| IkReal x960=((1.0)*new_r00); |
| IkReal x961=((((-1.0)*sj2*x960))+((cj2*new_r10))); |
| j0eval[0]=x961; |
| j0eval[1]=IKsign(x961); |
| j0eval[2]=((IKabs(((cj2*cj2)+(((-1.0)*new_r00*x960)))))+(IKabs((((cj2*sj2))+(((-1.0)*new_r10*x960)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[1]; |
| bool bgotonextstatement = true; |
| do |
| { |
| IkReal x962=((-1.0)*new_r00); |
| IkReal x964 = ((new_r10*new_r10)+(new_r00*new_r00)); |
| if(IKabs(x964)==0){ |
| continue; |
| } |
| IkReal x963=pow(x964,-0.5); |
| CheckValue<IkReal> x965 = IKatan2WithCheck(IkReal(new_r10),IkReal(x962),IKFAST_ATAN2_MAGTHRESH); |
| if(!x965.valid){ |
| continue; |
| } |
| IkReal gconst28=((-1.0)*(x965.value)); |
| IkReal gconst29=((-1.0)*new_r10*x963); |
| IkReal gconst30=(x962*x963); |
| CheckValue<IkReal> x966 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x966.valid){ |
| continue; |
| } |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs((j2+(x966.value))))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| IkReal x967=((-1.0)*new_r00); |
| CheckValue<IkReal> x970 = IKatan2WithCheck(IkReal(new_r10),IkReal(x967),IKFAST_ATAN2_MAGTHRESH); |
| if(!x970.valid){ |
| continue; |
| } |
| IkReal x968=((-1.0)*(x970.value)); |
| IkReal x969=x963; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x968; |
| IkReal gconst28=x968; |
| IkReal gconst29=((-1.0)*new_r10*x969); |
| IkReal gconst30=(x967*x969); |
| IkReal x971=new_r10*new_r10; |
| IkReal x972=(new_r00*new_r11); |
| IkReal x973=((((-1.0)*x972))+((new_r01*new_r10))); |
| IkReal x974=x963; |
| IkReal x975=((1.0)*new_r00*x974); |
| j0eval[0]=x973; |
| j0eval[1]=IKsign(x973); |
| j0eval[2]=((IKabs(((((-1.0)*new_r01*x975))+(((-1.0)*new_r10*x975)))))+(IKabs((((x971*x974))+((x972*x974)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x976=((-1.0)*new_r00); |
| CheckValue<IkReal> x979 = IKatan2WithCheck(IkReal(new_r10),IkReal(x976),IKFAST_ATAN2_MAGTHRESH); |
| if(!x979.valid){ |
| continue; |
| } |
| IkReal x977=((-1.0)*(x979.value)); |
| IkReal x978=x963; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x977; |
| IkReal gconst28=x977; |
| IkReal gconst29=((-1.0)*new_r10*x978); |
| IkReal gconst30=(x976*x978); |
| IkReal x980=new_r10*new_r10; |
| CheckValue<IkReal> x983=IKPowWithIntegerCheck((x980+(new_r00*new_r00)),-1); |
| if(!x983.valid){ |
| continue; |
| } |
| IkReal x981=x983.value; |
| IkReal x982=(new_r00*x981); |
| j0eval[0]=((IKabs((((new_r00*new_r11))+((x980*x981)))))+(IKabs((((new_r01*x982*(new_r00*new_r00)))+((new_r10*x982))+((new_r01*x980*x982)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x984=((-1.0)*new_r00); |
| CheckValue<IkReal> x987 = IKatan2WithCheck(IkReal(new_r10),IkReal(x984),IKFAST_ATAN2_MAGTHRESH); |
| if(!x987.valid){ |
| continue; |
| } |
| IkReal x985=((-1.0)*(x987.value)); |
| IkReal x986=x963; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x985; |
| IkReal gconst28=x985; |
| IkReal gconst29=((-1.0)*new_r10*x986); |
| IkReal gconst30=(x984*x986); |
| IkReal x988=new_r10*new_r10; |
| IkReal x989=(((new_r10*new_r11))+((new_r00*new_r01))); |
| IkReal x990=x963; |
| IkReal x991=((1.0)*new_r10*x990); |
| j0eval[0]=x989; |
| j0eval[1]=IKsign(x989); |
| j0eval[2]=((IKabs(((((-1.0)*new_r11*x991))+(((-1.0)*new_r00*x991)))))+(IKabs((((x988*x990))+(((-1.0)*new_r01*x991)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[2]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x993 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x993.valid){ |
| continue; |
| } |
| IkReal x992=((-1.0)*(x993.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x992; |
| new_r11=0; |
| new_r00=0; |
| IkReal gconst28=x992; |
| IkReal x994 = new_r10*new_r10; |
| if(IKabs(x994)==0){ |
| continue; |
| } |
| IkReal gconst29=((-1.0)*new_r10*(pow(x994,-0.5))); |
| IkReal gconst30=0; |
| j0eval[0]=new_r01; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x995=IKPowWithIntegerCheck(gconst29,-1); |
| if(!x995.valid){ |
| continue; |
| } |
| sj0array[0]=(new_r01*(x995.value)); |
| if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKasin(sj0array[0]); |
| cj0array[0] = IKcos(j0array[0]); |
| sj0array[1] = sj0array[0]; |
| j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| cj0array[1] = -cj0array[0]; |
| } |
| else if( isnan(sj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x996=IKcos(j0); |
| IkReal x997=IKsin(j0); |
| IkReal x998=((1.0)*gconst29); |
| IkReal x999=((-1.0)*x996); |
| evalcond[0]=(new_r01*x996); |
| evalcond[1]=(new_r10*x999); |
| evalcond[2]=(gconst29*x999); |
| evalcond[3]=(gconst29+(((-1.0)*new_r01*x997))); |
| evalcond[4]=((((-1.0)*x997*x998))+new_r10); |
| evalcond[5]=(((new_r10*x997))+(((-1.0)*x998))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1000=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x1000.valid){ |
| continue; |
| } |
| sj0array[0]=(gconst29*(x1000.value)); |
| if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKasin(sj0array[0]); |
| cj0array[0] = IKcos(j0array[0]); |
| sj0array[1] = sj0array[0]; |
| j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| cj0array[1] = -cj0array[0]; |
| } |
| else if( isnan(sj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1001=IKcos(j0); |
| IkReal x1002=IKsin(j0); |
| IkReal x1003=((1.0)*gconst29); |
| IkReal x1004=(x1002*x1003); |
| IkReal x1005=((-1.0)*x1001); |
| evalcond[0]=(new_r01*x1001); |
| evalcond[1]=(new_r10*x1005); |
| evalcond[2]=(gconst29*x1005); |
| evalcond[3]=((((-1.0)*x1004))+new_r01); |
| evalcond[4]=((((-1.0)*x1004))+new_r10); |
| evalcond[5]=((((-1.0)*x1003))+((new_r10*x1002))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| evalcond[1]=gconst29; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| IkReal x1006=((-1.0)*new_r00); |
| CheckValue<IkReal> x1008 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1006),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1008.valid){ |
| continue; |
| } |
| IkReal x1007=((-1.0)*(x1008.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1007; |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst28=x1007; |
| IkReal gconst29=((-1.0)*new_r10); |
| IkReal gconst30=x1006; |
| j0eval[0]=-1.0; |
| j0eval[1]=-1.0; |
| j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x1009=((-1.0)*new_r00); |
| CheckValue<IkReal> x1011 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1009),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1011.valid){ |
| continue; |
| } |
| IkReal x1010=((-1.0)*(x1011.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1010; |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst28=x1010; |
| IkReal gconst29=((-1.0)*new_r10); |
| IkReal gconst30=x1009; |
| j0eval[0]=1.0; |
| j0eval[1]=1.0; |
| j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x1012=((-1.0)*new_r00); |
| CheckValue<IkReal> x1014 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1012),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1014.valid){ |
| continue; |
| } |
| IkReal x1013=((-1.0)*(x1014.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1013; |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst28=x1013; |
| IkReal gconst29=((-1.0)*new_r10); |
| IkReal gconst30=x1012; |
| j0eval[0]=1.0; |
| j0eval[1]=1.0; |
| j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1015=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst29*new_r10))+(((-1.0)*gconst30*new_r00)))),-1); |
| if(!x1015.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1016 = IKatan2WithCheck(IkReal(gconst30*gconst30),IkReal(((-1.0)*gconst29*gconst30)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1016.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1015.value)))+(x1016.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1017=IKsin(j0); |
| IkReal x1018=IKcos(j0); |
| IkReal x1019=((1.0)*x1017); |
| IkReal x1020=(gconst29*x1018); |
| IkReal x1021=((1.0)*x1018); |
| IkReal x1022=(((gconst30*x1021))+((gconst29*x1019))); |
| evalcond[0]=(x1020+(((-1.0)*gconst30*x1019))); |
| evalcond[1]=(gconst30+(((-1.0)*new_r10*x1021))+((new_r00*x1017))); |
| evalcond[2]=((((-1.0)*x1020))+((gconst30*x1017))+new_r00); |
| evalcond[3]=((-1.0)*x1022); |
| evalcond[4]=(((new_r10*x1017))+((new_r00*x1018))+(((-1.0)*gconst29))); |
| evalcond[5]=((((-1.0)*x1022))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1023=IKPowWithIntegerCheck(IKsign(((gconst29*gconst29)+(gconst30*gconst30))),-1); |
| if(!x1023.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1024 = IKatan2WithCheck(IkReal((gconst29*new_r10)),IkReal((gconst30*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1024.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1023.value)))+(x1024.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1025=IKsin(j0); |
| IkReal x1026=IKcos(j0); |
| IkReal x1027=((1.0)*x1025); |
| IkReal x1028=(gconst29*x1026); |
| IkReal x1029=((1.0)*x1026); |
| IkReal x1030=(((gconst30*x1029))+((gconst29*x1027))); |
| evalcond[0]=(x1028+(((-1.0)*gconst30*x1027))); |
| evalcond[1]=(gconst30+(((-1.0)*new_r10*x1029))+((new_r00*x1025))); |
| evalcond[2]=((((-1.0)*x1028))+((gconst30*x1025))+new_r00); |
| evalcond[3]=((-1.0)*x1030); |
| evalcond[4]=(((new_r10*x1025))+(((-1.0)*gconst29))+((new_r00*x1026))); |
| evalcond[5]=((((-1.0)*x1030))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1031=IKPowWithIntegerCheck(IKsign((((gconst29*new_r10))+((gconst30*new_r00)))),-1); |
| if(!x1031.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1032 = IKatan2WithCheck(IkReal(gconst29*gconst29),IkReal((gconst29*gconst30)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1032.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1031.value)))+(x1032.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1033=IKsin(j0); |
| IkReal x1034=IKcos(j0); |
| IkReal x1035=((1.0)*x1033); |
| IkReal x1036=(gconst29*x1034); |
| IkReal x1037=((1.0)*x1034); |
| IkReal x1038=(((gconst30*x1037))+((gconst29*x1035))); |
| evalcond[0]=(x1036+(((-1.0)*gconst30*x1035))); |
| evalcond[1]=(gconst30+(((-1.0)*new_r10*x1037))+((new_r00*x1033))); |
| evalcond[2]=((((-1.0)*x1036))+((gconst30*x1033))+new_r00); |
| evalcond[3]=((-1.0)*x1038); |
| evalcond[4]=(((new_r10*x1033))+(((-1.0)*gconst29))+((new_r00*x1034))); |
| evalcond[5]=((((-1.0)*x1038))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1039=IKPowWithIntegerCheck(gconst30,-1); |
| if(!x1039.valid){ |
| continue; |
| } |
| sj0array[0]=(new_r11*(x1039.value)); |
| if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKasin(sj0array[0]); |
| cj0array[0] = IKcos(j0array[0]); |
| sj0array[1] = sj0array[0]; |
| j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| cj0array[1] = -cj0array[0]; |
| } |
| else if( isnan(sj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1040=IKcos(j0); |
| IkReal x1041=IKsin(j0); |
| evalcond[0]=(new_r11*x1040); |
| evalcond[1]=(new_r00*x1040); |
| evalcond[2]=((-1.0)*gconst30*x1040); |
| evalcond[3]=(gconst30+((new_r00*x1041))); |
| evalcond[4]=(new_r00+((gconst30*x1041))); |
| evalcond[5]=(((new_r11*x1041))+(((-1.0)*gconst30))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| IkReal x1042=((-1.0)*new_r00); |
| CheckValue<IkReal> x1044 = IKatan2WithCheck(IkReal(0),IkReal(x1042),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1044.valid){ |
| continue; |
| } |
| IkReal x1043=((-1.0)*(x1044.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1043; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst28=x1043; |
| IkReal gconst29=0; |
| IkReal x1045 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x1045)==0){ |
| continue; |
| } |
| IkReal gconst30=(x1042*(pow(x1045,-0.5))); |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x1046=((-1.0)*new_r00); |
| CheckValue<IkReal> x1048 = IKatan2WithCheck(IkReal(0),IkReal(x1046),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1048.valid){ |
| continue; |
| } |
| IkReal x1047=((-1.0)*(x1048.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1047; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst28=x1047; |
| IkReal gconst29=0; |
| IkReal x1049 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x1049)==0){ |
| continue; |
| } |
| IkReal gconst30=(x1046*(pow(x1049,-0.5))); |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| IkReal x1050=((-1.0)*new_r00); |
| CheckValue<IkReal> x1052 = IKatan2WithCheck(IkReal(0),IkReal(x1050),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1052.valid){ |
| continue; |
| } |
| IkReal x1051=((-1.0)*(x1052.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1051; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst28=x1051; |
| IkReal gconst29=0; |
| IkReal x1053 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x1053)==0){ |
| continue; |
| } |
| IkReal gconst30=(x1050*(pow(x1053,-0.5))); |
| j0eval[0]=new_r00; |
| j0eval[1]=new_r01; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1054=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1054.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1055=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x1055.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst30*(x1054.value)), (gconst30*(x1055.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1056=IKsin(j0); |
| IkReal x1057=IKcos(j0); |
| IkReal x1058=((1.0)*gconst30); |
| IkReal x1059=((-1.0)*gconst30); |
| evalcond[0]=(new_r00*x1057); |
| evalcond[1]=((-1.0)*new_r01*x1056); |
| evalcond[2]=(x1056*x1059); |
| evalcond[3]=(x1057*x1059); |
| evalcond[4]=(gconst30+((new_r00*x1056))); |
| evalcond[5]=(((gconst30*x1056))+new_r00); |
| evalcond[6]=((((-1.0)*x1057*x1058))+new_r01); |
| evalcond[7]=((((-1.0)*x1058))+((new_r01*x1057))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1060=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1060.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1061=IKPowWithIntegerCheck(gconst30,-1); |
| if(!x1061.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst30*(x1060.value)), (new_r01*(x1061.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1062=IKsin(j0); |
| IkReal x1063=IKcos(j0); |
| IkReal x1064=((1.0)*gconst30); |
| IkReal x1065=((-1.0)*gconst30); |
| evalcond[0]=(new_r00*x1063); |
| evalcond[1]=((-1.0)*new_r01*x1062); |
| evalcond[2]=(x1062*x1065); |
| evalcond[3]=(x1063*x1065); |
| evalcond[4]=(gconst30+((new_r00*x1062))); |
| evalcond[5]=(((gconst30*x1062))+new_r00); |
| evalcond[6]=((((-1.0)*x1063*x1064))+new_r01); |
| evalcond[7]=(((new_r01*x1063))+(((-1.0)*x1064))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1066=IKPowWithIntegerCheck(IKsign(gconst30),-1); |
| if(!x1066.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1067 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1067.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1066.value)))+(x1067.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1068=IKsin(j0); |
| IkReal x1069=IKcos(j0); |
| IkReal x1070=((1.0)*gconst30); |
| IkReal x1071=((-1.0)*gconst30); |
| evalcond[0]=(new_r00*x1069); |
| evalcond[1]=((-1.0)*new_r01*x1068); |
| evalcond[2]=(x1068*x1071); |
| evalcond[3]=(x1069*x1071); |
| evalcond[4]=(gconst30+((new_r00*x1068))); |
| evalcond[5]=(((gconst30*x1068))+new_r00); |
| evalcond[6]=(new_r01+(((-1.0)*x1069*x1070))); |
| evalcond[7]=(((new_r01*x1069))+(((-1.0)*x1070))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=IKabs(new_r10); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| IkReal x1072=((-1.0)*new_r00); |
| CheckValue<IkReal> x1074 = IKatan2WithCheck(IkReal(0),IkReal(x1072),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1074.valid){ |
| continue; |
| } |
| IkReal x1073=((-1.0)*(x1074.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1073; |
| new_r10=0; |
| IkReal gconst28=x1073; |
| IkReal gconst29=0; |
| IkReal x1075 = new_r00*new_r00; |
| if(IKabs(x1075)==0){ |
| continue; |
| } |
| IkReal gconst30=(x1072*(pow(x1075,-0.5))); |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x1076=((-1.0)*new_r00); |
| CheckValue<IkReal> x1078 = IKatan2WithCheck(IkReal(0),IkReal(x1076),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1078.valid){ |
| continue; |
| } |
| IkReal x1077=((-1.0)*(x1078.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1077; |
| new_r10=0; |
| IkReal gconst28=x1077; |
| IkReal gconst29=0; |
| IkReal x1079 = new_r00*new_r00; |
| if(IKabs(x1079)==0){ |
| continue; |
| } |
| IkReal gconst30=(x1076*(pow(x1079,-0.5))); |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x1080=((-1.0)*new_r00); |
| CheckValue<IkReal> x1082 = IKatan2WithCheck(IkReal(0),IkReal(x1080),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1082.valid){ |
| continue; |
| } |
| IkReal x1081=((-1.0)*(x1082.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1081; |
| new_r10=0; |
| IkReal gconst28=x1081; |
| IkReal gconst29=0; |
| IkReal x1083 = new_r00*new_r00; |
| if(IKabs(x1083)==0){ |
| continue; |
| } |
| IkReal gconst30=(x1080*(pow(x1083,-0.5))); |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1084=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1084.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1085=IKPowWithIntegerCheck(gconst30,-1); |
| if(!x1085.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst30*(x1084.value)), (new_r01*(x1085.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1086=IKcos(j0); |
| IkReal x1087=IKsin(j0); |
| IkReal x1088=((1.0)*gconst30); |
| evalcond[0]=(new_r00*x1086); |
| evalcond[1]=((-1.0)*gconst30*x1086); |
| evalcond[2]=(((new_r00*x1087))+gconst30); |
| evalcond[3]=(((gconst30*x1087))+new_r00); |
| evalcond[4]=((((-1.0)*x1087*x1088))+new_r11); |
| evalcond[5]=(new_r01+(((-1.0)*x1086*x1088))); |
| evalcond[6]=((((-1.0)*new_r01*x1087))+((new_r11*x1086))); |
| evalcond[7]=(((new_r01*x1086))+((new_r11*x1087))+(((-1.0)*x1088))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1089=IKPowWithIntegerCheck(IKsign(gconst30),-1); |
| if(!x1089.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1090 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1090.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1089.value)))+(x1090.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1091=IKcos(j0); |
| IkReal x1092=IKsin(j0); |
| IkReal x1093=((1.0)*gconst30); |
| evalcond[0]=(new_r00*x1091); |
| evalcond[1]=((-1.0)*gconst30*x1091); |
| evalcond[2]=(((new_r00*x1092))+gconst30); |
| evalcond[3]=(((gconst30*x1092))+new_r00); |
| evalcond[4]=((((-1.0)*x1092*x1093))+new_r11); |
| evalcond[5]=((((-1.0)*x1091*x1093))+new_r01); |
| evalcond[6]=(((new_r11*x1091))+(((-1.0)*new_r01*x1092))); |
| evalcond[7]=(((new_r11*x1092))+((new_r01*x1091))+(((-1.0)*x1093))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1094=IKPowWithIntegerCheck(IKsign(gconst30),-1); |
| if(!x1094.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1095 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1095.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1094.value)))+(x1095.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1096=IKcos(j0); |
| IkReal x1097=IKsin(j0); |
| IkReal x1098=((1.0)*gconst30); |
| evalcond[0]=(new_r00*x1096); |
| evalcond[1]=((-1.0)*gconst30*x1096); |
| evalcond[2]=(((new_r00*x1097))+gconst30); |
| evalcond[3]=(((gconst30*x1097))+new_r00); |
| evalcond[4]=((((-1.0)*x1097*x1098))+new_r11); |
| evalcond[5]=((((-1.0)*x1096*x1098))+new_r01); |
| evalcond[6]=(((new_r11*x1096))+(((-1.0)*new_r01*x1097))); |
| evalcond[7]=(((new_r11*x1097))+((new_r01*x1096))+(((-1.0)*x1098))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1100 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1100.valid){ |
| continue; |
| } |
| IkReal x1099=((-1.0)*(x1100.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1099; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst28=x1099; |
| IkReal x1101 = new_r10*new_r10; |
| if(IKabs(x1101)==0){ |
| continue; |
| } |
| IkReal gconst29=((-1.0)*new_r10*(pow(x1101,-0.5))); |
| IkReal gconst30=0; |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1103 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1103.valid){ |
| continue; |
| } |
| IkReal x1102=((-1.0)*(x1103.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1102; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst28=x1102; |
| IkReal x1104 = new_r10*new_r10; |
| if(IKabs(x1104)==0){ |
| continue; |
| } |
| IkReal gconst29=((-1.0)*new_r10*(pow(x1104,-0.5))); |
| IkReal gconst30=0; |
| j0eval[0]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| CheckValue<IkReal> x1106 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1106.valid){ |
| continue; |
| } |
| IkReal x1105=((-1.0)*(x1106.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst29; |
| cj2=gconst30; |
| j2=x1105; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst28=x1105; |
| IkReal x1107 = new_r10*new_r10; |
| if(IKabs(x1107)==0){ |
| continue; |
| } |
| IkReal gconst29=((-1.0)*new_r10*(pow(x1107,-0.5))); |
| IkReal gconst30=0; |
| j0eval[0]=new_r10; |
| j0eval[1]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1108=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x1108.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1109=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1109.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((gconst29*(x1108.value)), ((-1.0)*gconst29*(x1109.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1110=IKcos(j0); |
| IkReal x1111=IKsin(j0); |
| IkReal x1112=((1.0)*gconst29); |
| IkReal x1113=(gconst29*x1110); |
| evalcond[0]=(new_r11*x1111); |
| evalcond[1]=((-1.0)*new_r10*x1110); |
| evalcond[2]=((-1.0)*x1113); |
| evalcond[3]=((-1.0)*gconst29*x1111); |
| evalcond[4]=(gconst29+((new_r11*x1110))); |
| evalcond[5]=(x1113+new_r11); |
| evalcond[6]=(new_r10+(((-1.0)*x1111*x1112))); |
| evalcond[7]=(((new_r10*x1111))+(((-1.0)*x1112))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1114=IKPowWithIntegerCheck(gconst29,-1); |
| if(!x1114.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1115=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1115.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((new_r10*(x1114.value)), ((-1.0)*gconst29*(x1115.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1116=IKcos(j0); |
| IkReal x1117=IKsin(j0); |
| IkReal x1118=((1.0)*gconst29); |
| IkReal x1119=(gconst29*x1116); |
| evalcond[0]=(new_r11*x1117); |
| evalcond[1]=((-1.0)*new_r10*x1116); |
| evalcond[2]=((-1.0)*x1119); |
| evalcond[3]=((-1.0)*gconst29*x1117); |
| evalcond[4]=(gconst29+((new_r11*x1116))); |
| evalcond[5]=(x1119+new_r11); |
| evalcond[6]=(new_r10+(((-1.0)*x1117*x1118))); |
| evalcond[7]=(((new_r10*x1117))+(((-1.0)*x1118))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1120 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1120.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1121=IKPowWithIntegerCheck(IKsign(gconst29),-1); |
| if(!x1121.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1120.value)+(((1.5707963267949)*(x1121.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1122=IKcos(j0); |
| IkReal x1123=IKsin(j0); |
| IkReal x1124=((1.0)*gconst29); |
| IkReal x1125=(gconst29*x1122); |
| evalcond[0]=(new_r11*x1123); |
| evalcond[1]=((-1.0)*new_r10*x1122); |
| evalcond[2]=((-1.0)*x1125); |
| evalcond[3]=((-1.0)*gconst29*x1123); |
| evalcond[4]=(gconst29+((new_r11*x1122))); |
| evalcond[5]=(x1125+new_r11); |
| evalcond[6]=((((-1.0)*x1123*x1124))+new_r10); |
| evalcond[7]=(((new_r10*x1123))+(((-1.0)*x1124))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1126 = IKatan2WithCheck(IkReal((((gconst29*new_r11))+((gconst29*new_r00)))),IkReal((((gconst29*new_r01))+(((-1.0)*gconst29*new_r10)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1126.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1127=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| if(!x1127.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1126.value)+(((1.5707963267949)*(x1127.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1128=IKsin(j0); |
| IkReal x1129=IKcos(j0); |
| IkReal x1130=((1.0)*gconst30); |
| IkReal x1131=((1.0)*gconst29); |
| IkReal x1132=(gconst29*x1129); |
| IkReal x1133=(((x1129*x1130))+((x1128*x1131))); |
| evalcond[0]=((((-1.0)*new_r01*x1128))+gconst29+((new_r11*x1129))); |
| evalcond[1]=(gconst30+((new_r00*x1128))+(((-1.0)*new_r10*x1129))); |
| evalcond[2]=(((gconst30*x1128))+new_r00+(((-1.0)*x1129*x1131))); |
| evalcond[3]=(x1132+(((-1.0)*x1128*x1130))+new_r11); |
| evalcond[4]=(((new_r10*x1128))+(((-1.0)*x1131))+((new_r00*x1129))); |
| evalcond[5]=((((-1.0)*x1130))+((new_r01*x1129))+((new_r11*x1128))); |
| evalcond[6]=((((-1.0)*x1133))+new_r01); |
| evalcond[7]=((((-1.0)*x1133))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1134 = IKatan2WithCheck(IkReal(((gconst29*gconst29)+((new_r00*new_r11)))),IkReal((((new_r00*new_r01))+((gconst29*gconst30)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1134.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1135=IKPowWithIntegerCheck(IKsign((((gconst29*new_r01))+(((-1.0)*gconst30*new_r11)))),-1); |
| if(!x1135.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1134.value)+(((1.5707963267949)*(x1135.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1136=IKsin(j0); |
| IkReal x1137=IKcos(j0); |
| IkReal x1138=((1.0)*gconst30); |
| IkReal x1139=((1.0)*gconst29); |
| IkReal x1140=(gconst29*x1137); |
| IkReal x1141=(((x1136*x1139))+((x1137*x1138))); |
| evalcond[0]=((((-1.0)*new_r01*x1136))+gconst29+((new_r11*x1137))); |
| evalcond[1]=(gconst30+((new_r00*x1136))+(((-1.0)*new_r10*x1137))); |
| evalcond[2]=(((gconst30*x1136))+new_r00+(((-1.0)*x1137*x1139))); |
| evalcond[3]=(x1140+(((-1.0)*x1136*x1138))+new_r11); |
| evalcond[4]=((((-1.0)*x1139))+((new_r00*x1137))+((new_r10*x1136))); |
| evalcond[5]=((((-1.0)*x1138))+((new_r11*x1136))+((new_r01*x1137))); |
| evalcond[6]=((((-1.0)*x1141))+new_r01); |
| evalcond[7]=((((-1.0)*x1141))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1142 = IKatan2WithCheck(IkReal((((gconst29*new_r10))+((gconst30*new_r11)))),IkReal((((gconst29*new_r00))+((gconst30*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1142.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1143=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| if(!x1143.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1142.value)+(((1.5707963267949)*(x1143.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1144=IKsin(j0); |
| IkReal x1145=IKcos(j0); |
| IkReal x1146=((1.0)*gconst30); |
| IkReal x1147=((1.0)*gconst29); |
| IkReal x1148=(gconst29*x1145); |
| IkReal x1149=(((x1145*x1146))+((x1144*x1147))); |
| evalcond[0]=(gconst29+(((-1.0)*new_r01*x1144))+((new_r11*x1145))); |
| evalcond[1]=((((-1.0)*new_r10*x1145))+((new_r00*x1144))+gconst30); |
| evalcond[2]=((((-1.0)*x1145*x1147))+((gconst30*x1144))+new_r00); |
| evalcond[3]=(x1148+new_r11+(((-1.0)*x1144*x1146))); |
| evalcond[4]=(((new_r00*x1145))+(((-1.0)*x1147))+((new_r10*x1144))); |
| evalcond[5]=((((-1.0)*x1146))+((new_r01*x1145))+((new_r11*x1144))); |
| evalcond[6]=((((-1.0)*x1149))+new_r01); |
| evalcond[7]=((((-1.0)*x1149))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| IkReal x1152 = ((new_r10*new_r10)+(new_r00*new_r00)); |
| if(IKabs(x1152)==0){ |
| continue; |
| } |
| IkReal x1150=pow(x1152,-0.5); |
| IkReal x1151=((1.0)*x1150); |
| CheckValue<IkReal> x1153 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1153.valid){ |
| continue; |
| } |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*(x1153.value)))); |
| IkReal gconst32=(new_r10*x1151); |
| IkReal gconst33=(new_r00*x1151); |
| CheckValue<IkReal> x1154 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1154.valid){ |
| continue; |
| } |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j2+(x1154.value))))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x1158 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1158.valid){ |
| continue; |
| } |
| IkReal x1155=((1.0)*(x1158.value)); |
| IkReal x1156=x1150; |
| IkReal x1157=((1.0)*x1156); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1155))); |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1155))); |
| IkReal gconst32=(new_r10*x1157); |
| IkReal gconst33=(new_r00*x1157); |
| IkReal x1159=new_r10*new_r10; |
| IkReal x1160=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11))); |
| IkReal x1161=x1150; |
| IkReal x1162=(new_r00*x1161); |
| j0eval[0]=x1160; |
| j0eval[1]=IKsign(x1160); |
| j0eval[2]=((IKabs((((new_r10*x1162))+((new_r01*x1162)))))+(IKabs((((x1159*x1161))+((new_r11*x1162)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1166 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1166.valid){ |
| continue; |
| } |
| IkReal x1163=((1.0)*(x1166.value)); |
| IkReal x1164=x1150; |
| IkReal x1165=((1.0)*x1164); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1163))); |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1163))); |
| IkReal gconst32=(new_r10*x1165); |
| IkReal gconst33=(new_r00*x1165); |
| IkReal x1167=new_r10*new_r10; |
| IkReal x1168=new_r00*new_r00*new_r00; |
| CheckValue<IkReal> x1172=IKPowWithIntegerCheck((x1167+(new_r00*new_r00)),-1); |
| if(!x1172.valid){ |
| continue; |
| } |
| IkReal x1169=x1172.value; |
| IkReal x1170=(x1167*x1169); |
| IkReal x1171=(x1168*x1169); |
| 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)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x1176 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1176.valid){ |
| continue; |
| } |
| IkReal x1173=((1.0)*(x1176.value)); |
| IkReal x1174=x1150; |
| IkReal x1175=((1.0)*x1174); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1173))); |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1173))); |
| IkReal gconst32=(new_r10*x1175); |
| IkReal gconst33=(new_r00*x1175); |
| IkReal x1177=new_r10*new_r10; |
| IkReal x1178=(((new_r10*new_r11))+((new_r00*new_r01))); |
| IkReal x1179=x1150; |
| IkReal x1180=(new_r10*x1179); |
| j0eval[0]=x1178; |
| j0eval[1]=IKsign(x1178); |
| j0eval[2]=((IKabs((((new_r11*x1180))+((new_r00*x1180)))))+(IKabs(((((-1.0)*x1177*x1179))+((new_r01*x1180)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[2]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1182 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1182.valid){ |
| continue; |
| } |
| IkReal x1181=((1.0)*(x1182.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1181))); |
| new_r11=0; |
| new_r00=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1181))); |
| IkReal x1183 = new_r10*new_r10; |
| if(IKabs(x1183)==0){ |
| continue; |
| } |
| IkReal gconst32=((1.0)*new_r10*(pow(x1183,-0.5))); |
| IkReal gconst33=0; |
| j0eval[0]=new_r01; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1184=IKPowWithIntegerCheck(gconst32,-1); |
| if(!x1184.valid){ |
| continue; |
| } |
| sj0array[0]=(new_r01*(x1184.value)); |
| if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKasin(sj0array[0]); |
| cj0array[0] = IKcos(j0array[0]); |
| sj0array[1] = sj0array[0]; |
| j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| cj0array[1] = -cj0array[0]; |
| } |
| else if( isnan(sj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1185=IKcos(j0); |
| IkReal x1186=IKsin(j0); |
| IkReal x1187=((1.0)*gconst32); |
| IkReal x1188=((-1.0)*x1185); |
| evalcond[0]=(new_r01*x1185); |
| evalcond[1]=(new_r10*x1188); |
| evalcond[2]=(gconst32*x1188); |
| evalcond[3]=((((-1.0)*new_r01*x1186))+gconst32); |
| evalcond[4]=((((-1.0)*x1186*x1187))+new_r10); |
| evalcond[5]=((((-1.0)*x1187))+((new_r10*x1186))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1189=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x1189.valid){ |
| continue; |
| } |
| sj0array[0]=(gconst32*(x1189.value)); |
| if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKasin(sj0array[0]); |
| cj0array[0] = IKcos(j0array[0]); |
| sj0array[1] = sj0array[0]; |
| j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| cj0array[1] = -cj0array[0]; |
| } |
| else if( isnan(sj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1190=IKcos(j0); |
| IkReal x1191=IKsin(j0); |
| IkReal x1192=((1.0)*gconst32); |
| IkReal x1193=(x1191*x1192); |
| IkReal x1194=((-1.0)*x1190); |
| evalcond[0]=(new_r01*x1190); |
| evalcond[1]=(new_r10*x1194); |
| evalcond[2]=(gconst32*x1194); |
| evalcond[3]=((((-1.0)*x1193))+new_r01); |
| evalcond[4]=((((-1.0)*x1193))+new_r10); |
| evalcond[5]=((((-1.0)*x1192))+((new_r10*x1191))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| evalcond[1]=gconst32; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[4]; |
| CheckValue<IkReal> x1196 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1196.valid){ |
| continue; |
| } |
| IkReal x1195=((1.0)*(x1196.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1195))); |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1195))); |
| IkReal gconst32=((1.0)*new_r10); |
| IkReal gconst33=((1.0)*new_r00); |
| j0eval[0]=1.0; |
| j0eval[1]=new_r10; |
| j0eval[2]=1.0; |
| j0eval[3]=1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[4]; |
| CheckValue<IkReal> x1198 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1198.valid){ |
| continue; |
| } |
| IkReal x1197=((1.0)*(x1198.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1197))); |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1197))); |
| IkReal gconst32=((1.0)*new_r10); |
| IkReal gconst33=((1.0)*new_r00); |
| j0eval[0]=1.0; |
| j0eval[1]=new_r10; |
| j0eval[2]=1.0; |
| j0eval[3]=1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x1200 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1200.valid){ |
| continue; |
| } |
| IkReal x1199=((1.0)*(x1200.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1199))); |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1199))); |
| IkReal gconst32=((1.0)*new_r10); |
| IkReal gconst33=((1.0)*new_r00); |
| j0eval[0]=-1.0; |
| j0eval[1]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10)))); |
| j0eval[2]=-1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1201=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst33*new_r00))+(((-1.0)*gconst32*new_r10)))),-1); |
| if(!x1201.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1202 = IKatan2WithCheck(IkReal(gconst33*gconst33),IkReal(((-1.0)*gconst32*gconst33)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1202.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1201.value)))+(x1202.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1203=IKsin(j0); |
| IkReal x1204=IKcos(j0); |
| IkReal x1205=((1.0)*gconst32); |
| IkReal x1206=(gconst33*x1203); |
| IkReal x1207=((1.0)*x1204); |
| IkReal x1208=(((gconst33*x1207))+((x1203*x1205))); |
| evalcond[0]=((((-1.0)*x1206))+((gconst32*x1204))); |
| evalcond[1]=(((new_r00*x1203))+gconst33+(((-1.0)*new_r10*x1207))); |
| evalcond[2]=((((-1.0)*x1204*x1205))+x1206+new_r00); |
| evalcond[3]=((-1.0)*x1208); |
| evalcond[4]=(((new_r00*x1204))+((new_r10*x1203))+(((-1.0)*x1205))); |
| evalcond[5]=(new_r10+(((-1.0)*x1208))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1209=IKPowWithIntegerCheck(IKsign(((gconst32*gconst32)+(gconst33*gconst33))),-1); |
| if(!x1209.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1210 = IKatan2WithCheck(IkReal((gconst32*new_r10)),IkReal((gconst33*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1210.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1209.value)))+(x1210.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1211=IKsin(j0); |
| IkReal x1212=IKcos(j0); |
| IkReal x1213=((1.0)*gconst32); |
| IkReal x1214=(gconst33*x1211); |
| IkReal x1215=((1.0)*x1212); |
| IkReal x1216=(((gconst33*x1215))+((x1211*x1213))); |
| evalcond[0]=(((gconst32*x1212))+(((-1.0)*x1214))); |
| evalcond[1]=(gconst33+((new_r00*x1211))+(((-1.0)*new_r10*x1215))); |
| evalcond[2]=(x1214+(((-1.0)*x1212*x1213))+new_r00); |
| evalcond[3]=((-1.0)*x1216); |
| evalcond[4]=(((new_r10*x1211))+((new_r00*x1212))+(((-1.0)*x1213))); |
| evalcond[5]=(new_r10+(((-1.0)*x1216))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1217=IKPowWithIntegerCheck(IKsign((((gconst33*new_r00))+((gconst32*new_r10)))),-1); |
| if(!x1217.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1218 = IKatan2WithCheck(IkReal(gconst32*gconst32),IkReal((gconst32*gconst33)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1218.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1217.value)))+(x1218.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1219=IKsin(j0); |
| IkReal x1220=IKcos(j0); |
| IkReal x1221=((1.0)*gconst32); |
| IkReal x1222=(gconst33*x1219); |
| IkReal x1223=((1.0)*x1220); |
| IkReal x1224=(((x1219*x1221))+((gconst33*x1223))); |
| evalcond[0]=((((-1.0)*x1222))+((gconst32*x1220))); |
| evalcond[1]=(gconst33+((new_r00*x1219))+(((-1.0)*new_r10*x1223))); |
| evalcond[2]=(x1222+(((-1.0)*x1220*x1221))+new_r00); |
| evalcond[3]=((-1.0)*x1224); |
| evalcond[4]=(((new_r10*x1219))+(((-1.0)*x1221))+((new_r00*x1220))); |
| evalcond[5]=((((-1.0)*x1224))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1225=IKPowWithIntegerCheck(gconst33,-1); |
| if(!x1225.valid){ |
| continue; |
| } |
| sj0array[0]=(new_r11*(x1225.value)); |
| if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKasin(sj0array[0]); |
| cj0array[0] = IKcos(j0array[0]); |
| sj0array[1] = sj0array[0]; |
| j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| cj0array[1] = -cj0array[0]; |
| } |
| else if( isnan(sj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1226=IKcos(j0); |
| IkReal x1227=IKsin(j0); |
| evalcond[0]=(new_r11*x1226); |
| evalcond[1]=(new_r00*x1226); |
| evalcond[2]=((-1.0)*gconst33*x1226); |
| evalcond[3]=(gconst33+((new_r00*x1227))); |
| evalcond[4]=(((gconst33*x1227))+new_r00); |
| evalcond[5]=(((new_r11*x1227))+(((-1.0)*gconst33))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1229 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1229.valid){ |
| continue; |
| } |
| IkReal x1228=((1.0)*(x1229.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1228))); |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1228))); |
| IkReal gconst32=0; |
| IkReal x1230 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x1230)==0){ |
| continue; |
| } |
| IkReal gconst33=((1.0)*new_r00*(pow(x1230,-0.5))); |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1232 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1232.valid){ |
| continue; |
| } |
| IkReal x1231=((1.0)*(x1232.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1231))); |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1231))); |
| IkReal gconst32=0; |
| IkReal x1233 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x1233)==0){ |
| continue; |
| } |
| IkReal gconst33=((1.0)*new_r00*(pow(x1233,-0.5))); |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| CheckValue<IkReal> x1235 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1235.valid){ |
| continue; |
| } |
| IkReal x1234=((1.0)*(x1235.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1234))); |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1234))); |
| IkReal gconst32=0; |
| IkReal x1236 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| if(IKabs(x1236)==0){ |
| continue; |
| } |
| IkReal gconst33=((1.0)*new_r00*(pow(x1236,-0.5))); |
| j0eval[0]=new_r00; |
| j0eval[1]=new_r01; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1237=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1237.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1238=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x1238.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst33*(x1237.value)), (gconst33*(x1238.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1239=IKsin(j0); |
| IkReal x1240=IKcos(j0); |
| IkReal x1241=((1.0)*gconst33); |
| IkReal x1242=(gconst33*x1239); |
| evalcond[0]=(new_r00*x1240); |
| evalcond[1]=((-1.0)*new_r01*x1239); |
| evalcond[2]=((-1.0)*x1242); |
| evalcond[3]=((-1.0)*gconst33*x1240); |
| evalcond[4]=(gconst33+((new_r00*x1239))); |
| evalcond[5]=(x1242+new_r00); |
| evalcond[6]=((((-1.0)*x1240*x1241))+new_r01); |
| evalcond[7]=((((-1.0)*x1241))+((new_r01*x1240))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1243=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1243.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1244=IKPowWithIntegerCheck(gconst33,-1); |
| if(!x1244.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst33*(x1243.value)), (new_r01*(x1244.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1245=IKsin(j0); |
| IkReal x1246=IKcos(j0); |
| IkReal x1247=((1.0)*gconst33); |
| IkReal x1248=(gconst33*x1245); |
| evalcond[0]=(new_r00*x1246); |
| evalcond[1]=((-1.0)*new_r01*x1245); |
| evalcond[2]=((-1.0)*x1248); |
| evalcond[3]=((-1.0)*gconst33*x1246); |
| evalcond[4]=(gconst33+((new_r00*x1245))); |
| evalcond[5]=(x1248+new_r00); |
| evalcond[6]=(new_r01+(((-1.0)*x1246*x1247))); |
| evalcond[7]=((((-1.0)*x1247))+((new_r01*x1246))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1249 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1249.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1250=IKPowWithIntegerCheck(IKsign(gconst33),-1); |
| if(!x1250.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1249.value)+(((1.5707963267949)*(x1250.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1251=IKsin(j0); |
| IkReal x1252=IKcos(j0); |
| IkReal x1253=((1.0)*gconst33); |
| IkReal x1254=(gconst33*x1251); |
| evalcond[0]=(new_r00*x1252); |
| evalcond[1]=((-1.0)*new_r01*x1251); |
| evalcond[2]=((-1.0)*x1254); |
| evalcond[3]=((-1.0)*gconst33*x1252); |
| evalcond[4]=(((new_r00*x1251))+gconst33); |
| evalcond[5]=(x1254+new_r00); |
| evalcond[6]=((((-1.0)*x1252*x1253))+new_r01); |
| evalcond[7]=((((-1.0)*x1253))+((new_r01*x1252))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=IKabs(new_r10); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1256 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1256.valid){ |
| continue; |
| } |
| IkReal x1255=((1.0)*(x1256.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1255))); |
| new_r10=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1255))); |
| IkReal gconst32=0; |
| IkReal x1257 = new_r00*new_r00; |
| if(IKabs(x1257)==0){ |
| continue; |
| } |
| IkReal gconst33=((1.0)*new_r00*(pow(x1257,-0.5))); |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1259 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1259.valid){ |
| continue; |
| } |
| IkReal x1258=((1.0)*(x1259.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1258))); |
| new_r10=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1258))); |
| IkReal gconst32=0; |
| IkReal x1260 = new_r00*new_r00; |
| if(IKabs(x1260)==0){ |
| continue; |
| } |
| IkReal gconst33=((1.0)*new_r00*(pow(x1260,-0.5))); |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1262 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1262.valid){ |
| continue; |
| } |
| IkReal x1261=((1.0)*(x1262.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1261))); |
| new_r10=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1261))); |
| IkReal gconst32=0; |
| IkReal x1263 = new_r00*new_r00; |
| if(IKabs(x1263)==0){ |
| continue; |
| } |
| IkReal gconst33=((1.0)*new_r00*(pow(x1263,-0.5))); |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1264=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1264.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1265=IKPowWithIntegerCheck(gconst33,-1); |
| if(!x1265.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst33*(x1264.value)), (new_r01*(x1265.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1266=IKcos(j0); |
| IkReal x1267=IKsin(j0); |
| IkReal x1268=((1.0)*gconst33); |
| evalcond[0]=(new_r00*x1266); |
| evalcond[1]=((-1.0)*gconst33*x1266); |
| evalcond[2]=(gconst33+((new_r00*x1267))); |
| evalcond[3]=(((gconst33*x1267))+new_r00); |
| evalcond[4]=((((-1.0)*x1267*x1268))+new_r11); |
| evalcond[5]=((((-1.0)*x1266*x1268))+new_r01); |
| evalcond[6]=((((-1.0)*new_r01*x1267))+((new_r11*x1266))); |
| evalcond[7]=(((new_r01*x1266))+((new_r11*x1267))+(((-1.0)*x1268))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1269 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1269.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1270=IKPowWithIntegerCheck(IKsign(gconst33),-1); |
| if(!x1270.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1269.value)+(((1.5707963267949)*(x1270.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1271=IKcos(j0); |
| IkReal x1272=IKsin(j0); |
| IkReal x1273=((1.0)*gconst33); |
| evalcond[0]=(new_r00*x1271); |
| evalcond[1]=((-1.0)*gconst33*x1271); |
| evalcond[2]=(((new_r00*x1272))+gconst33); |
| evalcond[3]=(((gconst33*x1272))+new_r00); |
| evalcond[4]=((((-1.0)*x1272*x1273))+new_r11); |
| evalcond[5]=((((-1.0)*x1271*x1273))+new_r01); |
| evalcond[6]=((((-1.0)*new_r01*x1272))+((new_r11*x1271))); |
| evalcond[7]=(((new_r01*x1271))+(((-1.0)*x1273))+((new_r11*x1272))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1274 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1274.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1275=IKPowWithIntegerCheck(IKsign(gconst33),-1); |
| if(!x1275.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1274.value)+(((1.5707963267949)*(x1275.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1276=IKcos(j0); |
| IkReal x1277=IKsin(j0); |
| IkReal x1278=((1.0)*gconst33); |
| evalcond[0]=(new_r00*x1276); |
| evalcond[1]=((-1.0)*gconst33*x1276); |
| evalcond[2]=(((new_r00*x1277))+gconst33); |
| evalcond[3]=(((gconst33*x1277))+new_r00); |
| evalcond[4]=((((-1.0)*x1277*x1278))+new_r11); |
| evalcond[5]=((((-1.0)*x1276*x1278))+new_r01); |
| evalcond[6]=((((-1.0)*new_r01*x1277))+((new_r11*x1276))); |
| evalcond[7]=(((new_r01*x1276))+(((-1.0)*x1278))+((new_r11*x1277))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1280 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1280.valid){ |
| continue; |
| } |
| IkReal x1279=((1.0)*(x1280.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1279))); |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1279))); |
| IkReal x1281 = new_r10*new_r10; |
| if(IKabs(x1281)==0){ |
| continue; |
| } |
| IkReal gconst32=((1.0)*new_r10*(pow(x1281,-0.5))); |
| IkReal gconst33=0; |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1283 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1283.valid){ |
| continue; |
| } |
| IkReal x1282=((1.0)*(x1283.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1282))); |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1282))); |
| IkReal x1284 = new_r10*new_r10; |
| if(IKabs(x1284)==0){ |
| continue; |
| } |
| IkReal gconst32=((1.0)*new_r10*(pow(x1284,-0.5))); |
| IkReal gconst33=0; |
| j0eval[0]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| CheckValue<IkReal> x1286 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1286.valid){ |
| continue; |
| } |
| IkReal x1285=((1.0)*(x1286.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst32; |
| cj2=gconst33; |
| j2=((3.14159265)+(((-1.0)*x1285))); |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst31=((3.14159265358979)+(((-1.0)*x1285))); |
| IkReal x1287 = new_r10*new_r10; |
| if(IKabs(x1287)==0){ |
| continue; |
| } |
| IkReal gconst32=((1.0)*new_r10*(pow(x1287,-0.5))); |
| IkReal gconst33=0; |
| j0eval[0]=new_r10; |
| j0eval[1]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1288=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x1288.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1289=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1289.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((gconst32*(x1288.value)), ((-1.0)*gconst32*(x1289.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1290=IKcos(j0); |
| IkReal x1291=IKsin(j0); |
| IkReal x1292=((1.0)*gconst32); |
| IkReal x1293=(gconst32*x1290); |
| evalcond[0]=(new_r11*x1291); |
| evalcond[1]=((-1.0)*new_r10*x1290); |
| evalcond[2]=((-1.0)*x1293); |
| evalcond[3]=((-1.0)*gconst32*x1291); |
| evalcond[4]=(gconst32+((new_r11*x1290))); |
| evalcond[5]=(x1293+new_r11); |
| evalcond[6]=(new_r10+(((-1.0)*x1291*x1292))); |
| evalcond[7]=((((-1.0)*x1292))+((new_r10*x1291))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1294=IKPowWithIntegerCheck(gconst32,-1); |
| if(!x1294.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1295=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1295.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((new_r10*(x1294.value)), ((-1.0)*gconst32*(x1295.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1296=IKcos(j0); |
| IkReal x1297=IKsin(j0); |
| IkReal x1298=((1.0)*gconst32); |
| IkReal x1299=(gconst32*x1296); |
| evalcond[0]=(new_r11*x1297); |
| evalcond[1]=((-1.0)*new_r10*x1296); |
| evalcond[2]=((-1.0)*x1299); |
| evalcond[3]=((-1.0)*gconst32*x1297); |
| evalcond[4]=(gconst32+((new_r11*x1296))); |
| evalcond[5]=(x1299+new_r11); |
| evalcond[6]=((((-1.0)*x1297*x1298))+new_r10); |
| evalcond[7]=((((-1.0)*x1298))+((new_r10*x1297))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1300 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1300.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1301=IKPowWithIntegerCheck(IKsign(gconst32),-1); |
| if(!x1301.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1300.value)+(((1.5707963267949)*(x1301.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1302=IKcos(j0); |
| IkReal x1303=IKsin(j0); |
| IkReal x1304=((1.0)*gconst32); |
| IkReal x1305=(gconst32*x1302); |
| evalcond[0]=(new_r11*x1303); |
| evalcond[1]=((-1.0)*new_r10*x1302); |
| evalcond[2]=((-1.0)*x1305); |
| evalcond[3]=((-1.0)*gconst32*x1303); |
| evalcond[4]=(gconst32+((new_r11*x1302))); |
| evalcond[5]=(x1305+new_r11); |
| evalcond[6]=((((-1.0)*x1303*x1304))+new_r10); |
| evalcond[7]=((((-1.0)*x1304))+((new_r10*x1303))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1306 = IKatan2WithCheck(IkReal((((gconst32*new_r11))+((gconst32*new_r00)))),IkReal(((((-1.0)*gconst32*new_r10))+((gconst32*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1306.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1307=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| if(!x1307.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1306.value)+(((1.5707963267949)*(x1307.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1308=IKsin(j0); |
| IkReal x1309=IKcos(j0); |
| IkReal x1310=((1.0)*gconst32); |
| IkReal x1311=(gconst33*x1308); |
| IkReal x1312=((1.0)*x1309); |
| IkReal x1313=(((gconst33*x1312))+((x1308*x1310))); |
| evalcond[0]=(gconst32+((new_r11*x1309))+(((-1.0)*new_r01*x1308))); |
| evalcond[1]=((((-1.0)*new_r10*x1312))+gconst33+((new_r00*x1308))); |
| evalcond[2]=(x1311+new_r00+(((-1.0)*x1309*x1310))); |
| evalcond[3]=((((-1.0)*x1311))+((gconst32*x1309))+new_r11); |
| evalcond[4]=((((-1.0)*x1310))+((new_r10*x1308))+((new_r00*x1309))); |
| evalcond[5]=(((new_r11*x1308))+(((-1.0)*gconst33))+((new_r01*x1309))); |
| evalcond[6]=((((-1.0)*x1313))+new_r01); |
| evalcond[7]=((((-1.0)*x1313))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1314=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst33*new_r11))+((gconst32*new_r01)))),-1); |
| if(!x1314.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1315 = IKatan2WithCheck(IkReal((((new_r00*new_r11))+(gconst32*gconst32))),IkReal((((gconst32*gconst33))+((new_r00*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1315.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1314.value)))+(x1315.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1316=IKsin(j0); |
| IkReal x1317=IKcos(j0); |
| IkReal x1318=((1.0)*gconst32); |
| IkReal x1319=(gconst33*x1316); |
| IkReal x1320=((1.0)*x1317); |
| IkReal x1321=(((gconst33*x1320))+((x1316*x1318))); |
| evalcond[0]=(gconst32+((new_r11*x1317))+(((-1.0)*new_r01*x1316))); |
| evalcond[1]=(((new_r00*x1316))+(((-1.0)*new_r10*x1320))+gconst33); |
| evalcond[2]=(x1319+(((-1.0)*x1317*x1318))+new_r00); |
| evalcond[3]=((((-1.0)*x1319))+((gconst32*x1317))+new_r11); |
| evalcond[4]=(((new_r00*x1317))+(((-1.0)*x1318))+((new_r10*x1316))); |
| evalcond[5]=(((new_r01*x1317))+((new_r11*x1316))+(((-1.0)*gconst33))); |
| evalcond[6]=((((-1.0)*x1321))+new_r01); |
| evalcond[7]=((((-1.0)*x1321))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1322=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| if(!x1322.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1323 = IKatan2WithCheck(IkReal((((gconst33*new_r11))+((gconst32*new_r10)))),IkReal((((gconst33*new_r01))+((gconst32*new_r00)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1323.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1322.value)))+(x1323.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1324=IKsin(j0); |
| IkReal x1325=IKcos(j0); |
| IkReal x1326=((1.0)*gconst32); |
| IkReal x1327=(gconst33*x1324); |
| IkReal x1328=((1.0)*x1325); |
| IkReal x1329=(((gconst33*x1328))+((x1324*x1326))); |
| evalcond[0]=(gconst32+((new_r11*x1325))+(((-1.0)*new_r01*x1324))); |
| evalcond[1]=(((new_r00*x1324))+(((-1.0)*new_r10*x1328))+gconst33); |
| evalcond[2]=(x1327+(((-1.0)*x1325*x1326))+new_r00); |
| evalcond[3]=((((-1.0)*x1327))+((gconst32*x1325))+new_r11); |
| evalcond[4]=(((new_r00*x1325))+(((-1.0)*x1326))+((new_r10*x1324))); |
| evalcond[5]=(((new_r01*x1325))+((new_r11*x1324))+(((-1.0)*gconst33))); |
| evalcond[6]=((((-1.0)*x1329))+new_r01); |
| evalcond[7]=((((-1.0)*x1329))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| IkReal x1332 = ((new_r01*new_r01)+(new_r11*new_r11)); |
| if(IKabs(x1332)==0){ |
| continue; |
| } |
| IkReal x1330=pow(x1332,-0.5); |
| IkReal x1331=((-1.0)*x1330); |
| CheckValue<IkReal> x1333 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1333.valid){ |
| continue; |
| } |
| IkReal gconst34=((-1.0)*(x1333.value)); |
| IkReal gconst35=(new_r11*x1331); |
| IkReal gconst36=(new_r01*x1331); |
| CheckValue<IkReal> x1334 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1334.valid){ |
| continue; |
| } |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x1334.value)+j2)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x1338 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1338.valid){ |
| continue; |
| } |
| IkReal x1335=((-1.0)*(x1338.value)); |
| IkReal x1336=x1330; |
| IkReal x1337=((-1.0)*x1336); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1335; |
| IkReal gconst34=x1335; |
| IkReal gconst35=(new_r11*x1337); |
| IkReal gconst36=(new_r01*x1337); |
| IkReal x1339=new_r01*new_r01; |
| IkReal x1340=(new_r00*new_r11); |
| IkReal x1341=(((new_r01*new_r10))+(((-1.0)*x1340))); |
| IkReal x1342=x1330; |
| IkReal x1343=((1.0)*new_r11*x1342); |
| j0eval[0]=x1341; |
| j0eval[1]=IKsign(x1341); |
| j0eval[2]=((IKabs(((((-1.0)*new_r10*x1343))+(((-1.0)*new_r01*x1343)))))+(IKabs((((x1339*x1342))+((x1340*x1342)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x1347 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1347.valid){ |
| continue; |
| } |
| IkReal x1344=((-1.0)*(x1347.value)); |
| IkReal x1345=x1330; |
| IkReal x1346=((-1.0)*x1345); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1344; |
| IkReal gconst34=x1344; |
| IkReal gconst35=(new_r11*x1346); |
| IkReal gconst36=(new_r01*x1346); |
| IkReal x1348=new_r11*new_r11; |
| IkReal x1349=(((new_r10*new_r11))+((new_r00*new_r01))); |
| IkReal x1350=x1330; |
| IkReal x1351=(new_r11*x1350); |
| j0eval[0]=x1349; |
| j0eval[1]=IKsign(x1349); |
| j0eval[2]=((IKabs((((new_r10*x1351))+(((-1.0)*new_r01*x1351)))))+(IKabs(((((-1.0)*x1348*x1350))+(((-1.0)*new_r00*x1351)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1355 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1355.valid){ |
| continue; |
| } |
| IkReal x1352=((-1.0)*(x1355.value)); |
| IkReal x1353=x1330; |
| IkReal x1354=((-1.0)*x1353); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1352; |
| IkReal gconst34=x1352; |
| IkReal gconst35=(new_r11*x1354); |
| IkReal gconst36=(new_r01*x1354); |
| IkReal x1356=new_r01*new_r01; |
| CheckValue<IkReal> x1359=IKPowWithIntegerCheck((x1356+(new_r11*new_r11)),-1); |
| if(!x1359.valid){ |
| continue; |
| } |
| IkReal x1357=x1359.value; |
| IkReal x1358=((1.0)*x1357); |
| j0eval[0]=((IKabs(((((-1.0)*x1356*x1358))+(new_r00*new_r00))))+(IKabs((((new_r00*new_r10))+(((-1.0)*new_r01*new_r11*x1358)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[2]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| evalcond[1]=gconst36; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| IkReal x1360=((-1.0)*new_r01); |
| CheckValue<IkReal> x1362 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1360),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1362.valid){ |
| continue; |
| } |
| IkReal x1361=((-1.0)*(x1362.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1361; |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst34=x1361; |
| IkReal gconst35=((-1.0)*new_r11); |
| IkReal gconst36=x1360; |
| j0eval[0]=-1.0; |
| j0eval[1]=-1.0; |
| j0eval[2]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x1363=((-1.0)*new_r01); |
| CheckValue<IkReal> x1365 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1363),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1365.valid){ |
| continue; |
| } |
| IkReal x1364=((-1.0)*(x1365.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1364; |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst34=x1364; |
| IkReal gconst35=((-1.0)*new_r11); |
| IkReal gconst36=x1363; |
| j0eval[0]=1.0; |
| j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); |
| j0eval[2]=1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| IkReal x1366=((-1.0)*new_r01); |
| CheckValue<IkReal> x1368 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1366),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1368.valid){ |
| continue; |
| } |
| IkReal x1367=((-1.0)*(x1368.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1367; |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst34=x1367; |
| IkReal gconst35=((-1.0)*new_r11); |
| IkReal gconst36=x1366; |
| j0eval[0]=1.0; |
| j0eval[1]=1.0; |
| j0eval[2]=((IKabs((new_r01*new_r11)))+(IKabs(((1.0)+(((-1.0)*(new_r01*new_r01))))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1369=IKPowWithIntegerCheck(IKsign(((gconst35*gconst35)+(gconst36*gconst36))),-1); |
| if(!x1369.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1370 = IKatan2WithCheck(IkReal((gconst36*new_r11)),IkReal(((-1.0)*gconst35*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1370.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1369.value)))+(x1370.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1371=IKcos(j0); |
| IkReal x1372=IKsin(j0); |
| IkReal x1373=((1.0)*gconst36); |
| IkReal x1374=(gconst35*x1371); |
| IkReal x1375=(gconst36*x1372); |
| IkReal x1376=((1.0)*x1372); |
| IkReal x1377=(((gconst35*x1376))+((x1371*x1373))); |
| evalcond[0]=(x1375+(((-1.0)*x1374))); |
| evalcond[1]=((((-1.0)*new_r01*x1376))+gconst35+((new_r11*x1371))); |
| evalcond[2]=(x1374+(((-1.0)*x1372*x1373))+new_r11); |
| evalcond[3]=((-1.0)*x1377); |
| evalcond[4]=((((-1.0)*x1373))+((new_r11*x1372))+((new_r01*x1371))); |
| evalcond[5]=((((-1.0)*x1377))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1378 = IKatan2WithCheck(IkReal((gconst35*new_r01)),IkReal((gconst36*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1378.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1379=IKPowWithIntegerCheck(IKsign(((gconst35*gconst35)+(gconst36*gconst36))),-1); |
| if(!x1379.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1378.value)+(((1.5707963267949)*(x1379.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1380=IKcos(j0); |
| IkReal x1381=IKsin(j0); |
| IkReal x1382=((1.0)*gconst36); |
| IkReal x1383=(gconst35*x1380); |
| IkReal x1384=(gconst36*x1381); |
| IkReal x1385=((1.0)*x1381); |
| IkReal x1386=(((gconst35*x1385))+((x1380*x1382))); |
| evalcond[0]=(x1384+(((-1.0)*x1383))); |
| evalcond[1]=(((new_r11*x1380))+gconst35+(((-1.0)*new_r01*x1385))); |
| evalcond[2]=(x1383+(((-1.0)*x1381*x1382))+new_r11); |
| evalcond[3]=((-1.0)*x1386); |
| evalcond[4]=((((-1.0)*x1382))+((new_r11*x1381))+((new_r01*x1380))); |
| evalcond[5]=((((-1.0)*x1386))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1387=IKPowWithIntegerCheck(IKsign((((gconst36*new_r01))+((gconst35*new_r11)))),-1); |
| if(!x1387.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1388 = IKatan2WithCheck(IkReal((gconst35*gconst36)),IkReal(gconst36*gconst36),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1388.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1387.value)))+(x1388.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1389=IKcos(j0); |
| IkReal x1390=IKsin(j0); |
| IkReal x1391=((1.0)*gconst36); |
| IkReal x1392=(gconst35*x1389); |
| IkReal x1393=(gconst36*x1390); |
| IkReal x1394=((1.0)*x1390); |
| IkReal x1395=(((gconst35*x1394))+((x1389*x1391))); |
| evalcond[0]=(x1393+(((-1.0)*x1392))); |
| evalcond[1]=(((new_r11*x1389))+gconst35+(((-1.0)*new_r01*x1394))); |
| evalcond[2]=(x1392+(((-1.0)*x1390*x1391))+new_r11); |
| evalcond[3]=((-1.0)*x1395); |
| evalcond[4]=(((new_r11*x1390))+((new_r01*x1389))+(((-1.0)*x1391))); |
| evalcond[5]=(new_r01+(((-1.0)*x1395))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1397 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1397.valid){ |
| continue; |
| } |
| IkReal x1396=((-1.0)*(x1397.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1396; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst34=x1396; |
| IkReal x1398 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x1398)==0){ |
| continue; |
| } |
| IkReal gconst35=((-1.0)*new_r11*(pow(x1398,-0.5))); |
| IkReal gconst36=0; |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1400 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1400.valid){ |
| continue; |
| } |
| IkReal x1399=((-1.0)*(x1400.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1399; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst34=x1399; |
| IkReal x1401 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x1401)==0){ |
| continue; |
| } |
| IkReal gconst35=((-1.0)*new_r11*(pow(x1401,-0.5))); |
| IkReal gconst36=0; |
| j0eval[0]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| CheckValue<IkReal> x1403 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1403.valid){ |
| continue; |
| } |
| IkReal x1402=((-1.0)*(x1403.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1402; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst34=x1402; |
| IkReal x1404 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x1404)==0){ |
| continue; |
| } |
| IkReal gconst35=((-1.0)*new_r11*(pow(x1404,-0.5))); |
| IkReal gconst36=0; |
| j0eval[0]=new_r10; |
| j0eval[1]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1405=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x1405.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1406=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1406.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((gconst35*(x1405.value)), ((-1.0)*gconst35*(x1406.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1407=IKcos(j0); |
| IkReal x1408=IKsin(j0); |
| IkReal x1409=((1.0)*gconst35); |
| IkReal x1410=((-1.0)*x1407); |
| evalcond[0]=(new_r11*x1408); |
| evalcond[1]=(new_r10*x1410); |
| evalcond[2]=(gconst35*x1410); |
| evalcond[3]=((-1.0)*gconst35*x1408); |
| evalcond[4]=(gconst35+((new_r11*x1407))); |
| evalcond[5]=(new_r11+((gconst35*x1407))); |
| evalcond[6]=(new_r10+(((-1.0)*x1408*x1409))); |
| evalcond[7]=(((new_r10*x1408))+(((-1.0)*x1409))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1411=IKPowWithIntegerCheck(gconst35,-1); |
| if(!x1411.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1412=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1412.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((new_r10*(x1411.value)), ((-1.0)*gconst35*(x1412.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1413=IKcos(j0); |
| IkReal x1414=IKsin(j0); |
| IkReal x1415=((1.0)*gconst35); |
| IkReal x1416=((-1.0)*x1413); |
| evalcond[0]=(new_r11*x1414); |
| evalcond[1]=(new_r10*x1416); |
| evalcond[2]=(gconst35*x1416); |
| evalcond[3]=((-1.0)*gconst35*x1414); |
| evalcond[4]=(gconst35+((new_r11*x1413))); |
| evalcond[5]=(((gconst35*x1413))+new_r11); |
| evalcond[6]=((((-1.0)*x1414*x1415))+new_r10); |
| evalcond[7]=((((-1.0)*x1415))+((new_r10*x1414))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1417 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1417.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1418=IKPowWithIntegerCheck(IKsign(gconst35),-1); |
| if(!x1418.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1417.value)+(((1.5707963267949)*(x1418.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1419=IKcos(j0); |
| IkReal x1420=IKsin(j0); |
| IkReal x1421=((1.0)*gconst35); |
| IkReal x1422=((-1.0)*x1419); |
| evalcond[0]=(new_r11*x1420); |
| evalcond[1]=(new_r10*x1422); |
| evalcond[2]=(gconst35*x1422); |
| evalcond[3]=((-1.0)*gconst35*x1420); |
| evalcond[4]=(gconst35+((new_r11*x1419))); |
| evalcond[5]=(((gconst35*x1419))+new_r11); |
| evalcond[6]=((((-1.0)*x1420*x1421))+new_r10); |
| evalcond[7]=(((new_r10*x1420))+(((-1.0)*x1421))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| IkReal x1423=((-1.0)*new_r01); |
| CheckValue<IkReal> x1425 = IKatan2WithCheck(IkReal(0),IkReal(x1423),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1425.valid){ |
| continue; |
| } |
| IkReal x1424=((-1.0)*(x1425.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1424; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst34=x1424; |
| IkReal gconst35=0; |
| IkReal x1426 = new_r01*new_r01; |
| if(IKabs(x1426)==0){ |
| continue; |
| } |
| IkReal gconst36=(x1423*(pow(x1426,-0.5))); |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| IkReal x1427=((-1.0)*new_r01); |
| CheckValue<IkReal> x1429 = IKatan2WithCheck(IkReal(0),IkReal(x1427),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1429.valid){ |
| continue; |
| } |
| IkReal x1428=((-1.0)*(x1429.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1428; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst34=x1428; |
| IkReal gconst35=0; |
| IkReal x1430 = new_r01*new_r01; |
| if(IKabs(x1430)==0){ |
| continue; |
| } |
| IkReal gconst36=(x1427*(pow(x1430,-0.5))); |
| j0eval[0]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| IkReal x1431=((-1.0)*new_r01); |
| CheckValue<IkReal> x1433 = IKatan2WithCheck(IkReal(0),IkReal(x1431),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1433.valid){ |
| continue; |
| } |
| IkReal x1432=((-1.0)*(x1433.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst35; |
| cj2=gconst36; |
| j2=x1432; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| IkReal gconst34=x1432; |
| IkReal gconst35=0; |
| IkReal x1434 = new_r01*new_r01; |
| if(IKabs(x1434)==0){ |
| continue; |
| } |
| IkReal gconst36=(x1431*(pow(x1434,-0.5))); |
| j0eval[0]=new_r00; |
| j0eval[1]=new_r01; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1435=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1435.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1436=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x1436.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst36*(x1435.value)), (gconst36*(x1436.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1437=IKsin(j0); |
| IkReal x1438=IKcos(j0); |
| IkReal x1439=((1.0)*gconst36); |
| IkReal x1440=((-1.0)*x1437); |
| evalcond[0]=(new_r00*x1438); |
| evalcond[1]=(new_r01*x1440); |
| evalcond[2]=(gconst36*x1440); |
| evalcond[3]=((-1.0)*gconst36*x1438); |
| evalcond[4]=(((new_r00*x1437))+gconst36); |
| evalcond[5]=(((gconst36*x1437))+new_r00); |
| evalcond[6]=((((-1.0)*x1438*x1439))+new_r01); |
| evalcond[7]=(((new_r01*x1438))+(((-1.0)*x1439))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1441=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1441.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1442=IKPowWithIntegerCheck(gconst36,-1); |
| if(!x1442.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*gconst36*(x1441.value)), (new_r01*(x1442.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1443=IKsin(j0); |
| IkReal x1444=IKcos(j0); |
| IkReal x1445=((1.0)*gconst36); |
| IkReal x1446=((-1.0)*x1443); |
| evalcond[0]=(new_r00*x1444); |
| evalcond[1]=(new_r01*x1446); |
| evalcond[2]=(gconst36*x1446); |
| evalcond[3]=((-1.0)*gconst36*x1444); |
| evalcond[4]=(gconst36+((new_r00*x1443))); |
| evalcond[5]=(((gconst36*x1443))+new_r00); |
| evalcond[6]=(new_r01+(((-1.0)*x1444*x1445))); |
| evalcond[7]=(((new_r01*x1444))+(((-1.0)*x1445))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1447 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1447.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1448=IKPowWithIntegerCheck(IKsign(gconst36),-1); |
| if(!x1448.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1447.value)+(((1.5707963267949)*(x1448.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1449=IKsin(j0); |
| IkReal x1450=IKcos(j0); |
| IkReal x1451=((1.0)*gconst36); |
| IkReal x1452=((-1.0)*x1449); |
| evalcond[0]=(new_r00*x1450); |
| evalcond[1]=(new_r01*x1452); |
| evalcond[2]=(gconst36*x1452); |
| evalcond[3]=((-1.0)*gconst36*x1450); |
| evalcond[4]=(gconst36+((new_r00*x1449))); |
| evalcond[5]=(((gconst36*x1449))+new_r00); |
| evalcond[6]=(new_r01+(((-1.0)*x1450*x1451))); |
| evalcond[7]=((((-1.0)*x1451))+((new_r01*x1450))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x1453=((1.0)*gconst36); |
| CheckValue<IkReal> x1454=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x1453))+((gconst35*new_r00)))),-1); |
| if(!x1454.valid){ |
| continue; |
| } |
| 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); |
| if(!x1455.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1454.value)))+(x1455.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1456=IKsin(j0); |
| IkReal x1457=IKcos(j0); |
| IkReal x1458=((1.0)*gconst35); |
| IkReal x1459=(gconst35*x1457); |
| IkReal x1460=((1.0)*x1457); |
| IkReal x1461=(gconst36*x1456); |
| IkReal x1462=(((x1456*x1458))+((gconst36*x1460))); |
| evalcond[0]=(gconst35+((new_r11*x1457))+(((-1.0)*new_r01*x1456))); |
| evalcond[1]=((((-1.0)*new_r10*x1460))+gconst36+((new_r00*x1456))); |
| evalcond[2]=((((-1.0)*x1457*x1458))+x1461+new_r00); |
| evalcond[3]=(x1459+new_r11+(((-1.0)*x1461))); |
| evalcond[4]=((((-1.0)*x1458))+((new_r00*x1457))+((new_r10*x1456))); |
| evalcond[5]=(((new_r01*x1457))+((new_r11*x1456))+(((-1.0)*gconst36))); |
| evalcond[6]=((((-1.0)*x1462))+new_r01); |
| evalcond[7]=((((-1.0)*x1462))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1463 = IKatan2WithCheck(IkReal((((gconst35*new_r00))+((gconst35*new_r11)))),IkReal((((gconst35*new_r01))+(((-1.0)*gconst35*new_r10)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1463.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1464=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| if(!x1464.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1463.value)+(((1.5707963267949)*(x1464.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1465=IKsin(j0); |
| IkReal x1466=IKcos(j0); |
| IkReal x1467=((1.0)*gconst35); |
| IkReal x1468=(gconst35*x1466); |
| IkReal x1469=((1.0)*x1466); |
| IkReal x1470=(gconst36*x1465); |
| IkReal x1471=(((gconst36*x1469))+((x1465*x1467))); |
| evalcond[0]=((((-1.0)*new_r01*x1465))+gconst35+((new_r11*x1466))); |
| evalcond[1]=((((-1.0)*new_r10*x1469))+((new_r00*x1465))+gconst36); |
| evalcond[2]=((((-1.0)*x1466*x1467))+x1470+new_r00); |
| evalcond[3]=((((-1.0)*x1470))+x1468+new_r11); |
| evalcond[4]=(((new_r00*x1466))+(((-1.0)*x1467))+((new_r10*x1465))); |
| evalcond[5]=(((new_r01*x1466))+((new_r11*x1465))+(((-1.0)*gconst36))); |
| evalcond[6]=((((-1.0)*x1471))+new_r01); |
| evalcond[7]=((((-1.0)*x1471))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1472=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| if(!x1472.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1473 = IKatan2WithCheck(IkReal((((gconst36*new_r11))+((gconst35*new_r10)))),IkReal((((gconst35*new_r00))+((gconst36*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1473.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1472.value)))+(x1473.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1474=IKsin(j0); |
| IkReal x1475=IKcos(j0); |
| IkReal x1476=((1.0)*gconst35); |
| IkReal x1477=(gconst35*x1475); |
| IkReal x1478=((1.0)*x1475); |
| IkReal x1479=(gconst36*x1474); |
| IkReal x1480=(((x1474*x1476))+((gconst36*x1478))); |
| evalcond[0]=(((new_r11*x1475))+gconst35+(((-1.0)*new_r01*x1474))); |
| evalcond[1]=(gconst36+((new_r00*x1474))+(((-1.0)*new_r10*x1478))); |
| evalcond[2]=((((-1.0)*x1475*x1476))+x1479+new_r00); |
| evalcond[3]=((((-1.0)*x1479))+x1477+new_r11); |
| evalcond[4]=(((new_r10*x1474))+((new_r00*x1475))+(((-1.0)*x1476))); |
| evalcond[5]=(((new_r11*x1474))+((new_r01*x1475))+(((-1.0)*gconst36))); |
| evalcond[6]=((((-1.0)*x1480))+new_r01); |
| evalcond[7]=((((-1.0)*x1480))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| IkReal x1483 = ((new_r01*new_r01)+(new_r11*new_r11)); |
| if(IKabs(x1483)==0){ |
| continue; |
| } |
| IkReal x1481=pow(x1483,-0.5); |
| IkReal x1482=((1.0)*x1481); |
| CheckValue<IkReal> x1484 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1484.valid){ |
| continue; |
| } |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*(x1484.value)))); |
| IkReal gconst38=(new_r11*x1482); |
| IkReal gconst39=(new_r01*x1482); |
| CheckValue<IkReal> x1485 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1485.valid){ |
| continue; |
| } |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x1485.value)+j2)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x1489 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1489.valid){ |
| continue; |
| } |
| IkReal x1486=((1.0)*(x1489.value)); |
| IkReal x1487=x1481; |
| IkReal x1488=((1.0)*x1487); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1486))); |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1486))); |
| IkReal gconst38=(new_r11*x1488); |
| IkReal gconst39=(new_r01*x1488); |
| IkReal x1490=new_r01*new_r01; |
| IkReal x1491=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11))); |
| IkReal x1492=x1481; |
| IkReal x1493=(new_r11*x1492); |
| j0eval[0]=x1491; |
| j0eval[1]=IKsign(x1491); |
| j0eval[2]=((IKabs((((new_r00*x1493))+((x1490*x1492)))))+(IKabs((((new_r01*x1493))+((new_r10*x1493)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1497 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1497.valid){ |
| continue; |
| } |
| IkReal x1494=((1.0)*(x1497.value)); |
| IkReal x1495=x1481; |
| IkReal x1496=((1.0)*x1495); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1494))); |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1494))); |
| IkReal gconst38=(new_r11*x1496); |
| IkReal gconst39=(new_r01*x1496); |
| IkReal x1498=new_r01*new_r01; |
| IkReal x1499=new_r11*new_r11*new_r11; |
| CheckValue<IkReal> x1503=IKPowWithIntegerCheck(((new_r11*new_r11)+x1498),-1); |
| if(!x1503.valid){ |
| continue; |
| } |
| IkReal x1500=x1503.value; |
| IkReal x1501=(x1498*x1500); |
| IkReal x1502=(x1499*x1500); |
| 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)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x1507 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1507.valid){ |
| continue; |
| } |
| IkReal x1504=((1.0)*(x1507.value)); |
| IkReal x1505=x1481; |
| IkReal x1506=((1.0)*x1505); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1504))); |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1504))); |
| IkReal gconst38=(new_r11*x1506); |
| IkReal gconst39=(new_r01*x1506); |
| IkReal x1508=new_r11*new_r11; |
| IkReal x1509=(new_r10*new_r11); |
| IkReal x1510=(((new_r00*new_r01))+x1509); |
| IkReal x1511=x1481; |
| IkReal x1512=(new_r11*x1511); |
| j0eval[0]=x1510; |
| j0eval[1]=IKsign(x1510); |
| j0eval[2]=((IKabs(((((-1.0)*x1509*x1511))+((new_r01*x1512)))))+(IKabs((((x1508*x1511))+((new_r00*x1512)))))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[2]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1514 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1514.valid){ |
| continue; |
| } |
| IkReal x1513=((1.0)*(x1514.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1513))); |
| new_r11=0; |
| new_r00=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1513))); |
| IkReal gconst38=0; |
| IkReal x1515 = new_r01*new_r01; |
| if(IKabs(x1515)==0){ |
| continue; |
| } |
| IkReal gconst39=((1.0)*new_r01*(pow(x1515,-0.5))); |
| j0eval[0]=new_r10; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1516=IKPowWithIntegerCheck(gconst39,-1); |
| if(!x1516.valid){ |
| continue; |
| } |
| cj0array[0]=(new_r01*(x1516.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1517=IKsin(j0); |
| IkReal x1518=IKcos(j0); |
| IkReal x1519=((1.0)*x1518); |
| evalcond[0]=(new_r10*x1517); |
| evalcond[1]=(gconst39*x1517); |
| evalcond[2]=((-1.0)*new_r01*x1517); |
| evalcond[3]=((((-1.0)*new_r10*x1519))+gconst39); |
| evalcond[4]=((((-1.0)*gconst39*x1519))+new_r10); |
| evalcond[5]=(((new_r01*x1518))+(((-1.0)*gconst39))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1520=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x1520.valid){ |
| continue; |
| } |
| cj0array[0]=(gconst39*(x1520.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1521=IKsin(j0); |
| IkReal x1522=IKcos(j0); |
| IkReal x1523=((1.0)*gconst39); |
| IkReal x1524=(x1522*x1523); |
| evalcond[0]=(new_r10*x1521); |
| evalcond[1]=(gconst39*x1521); |
| evalcond[2]=((-1.0)*new_r01*x1521); |
| evalcond[3]=((((-1.0)*x1524))+new_r01); |
| evalcond[4]=((((-1.0)*x1524))+new_r10); |
| evalcond[5]=((((-1.0)*x1523))+((new_r01*x1522))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| evalcond[1]=gconst39; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[4]; |
| CheckValue<IkReal> x1526 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1526.valid){ |
| continue; |
| } |
| IkReal x1525=((1.0)*(x1526.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1525))); |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1525))); |
| IkReal gconst38=((1.0)*new_r11); |
| IkReal gconst39=((1.0)*new_r01); |
| j0eval[0]=1.0; |
| j0eval[1]=1.0; |
| j0eval[2]=new_r01; |
| j0eval[3]=1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[4]; |
| CheckValue<IkReal> x1528 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1528.valid){ |
| continue; |
| } |
| IkReal x1527=((1.0)*(x1528.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1527))); |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1527))); |
| IkReal gconst38=((1.0)*new_r11); |
| IkReal gconst39=((1.0)*new_r01); |
| j0eval[0]=1.0; |
| j0eval[1]=new_r01; |
| j0eval[2]=1.0; |
| j0eval[3]=1.0; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| CheckValue<IkReal> x1530 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1530.valid){ |
| continue; |
| } |
| IkReal x1529=((1.0)*(x1530.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1529))); |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1529))); |
| IkReal gconst38=((1.0)*new_r11); |
| IkReal gconst39=((1.0)*new_r01); |
| j0eval[0]=1.0; |
| j0eval[1]=1.0; |
| j0eval[2]=((IKabs(((-1.0)+(new_r01*new_r01))))+(IKabs(((1.0)*new_r01*new_r11)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1531 = IKatan2WithCheck(IkReal((gconst39*new_r11)),IkReal(((-1.0)*gconst38*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1531.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1532=IKPowWithIntegerCheck(IKsign(((gconst38*gconst38)+(gconst39*gconst39))),-1); |
| if(!x1532.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1531.value)+(((1.5707963267949)*(x1532.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1533=IKcos(j0); |
| IkReal x1534=IKsin(j0); |
| IkReal x1535=((1.0)*gconst39); |
| IkReal x1536=(gconst38*x1533); |
| IkReal x1537=((1.0)*x1534); |
| IkReal x1538=(((x1533*x1535))+((gconst38*x1537))); |
| evalcond[0]=(((gconst39*x1534))+(((-1.0)*x1536))); |
| evalcond[1]=(gconst38+(((-1.0)*new_r01*x1537))+((new_r11*x1533))); |
| evalcond[2]=(x1536+(((-1.0)*x1534*x1535))+new_r11); |
| evalcond[3]=((-1.0)*x1538); |
| evalcond[4]=((((-1.0)*x1535))+((new_r01*x1533))+((new_r11*x1534))); |
| evalcond[5]=((((-1.0)*x1538))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1539 = IKatan2WithCheck(IkReal((gconst38*new_r01)),IkReal((gconst39*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1539.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1540=IKPowWithIntegerCheck(IKsign(((gconst38*gconst38)+(gconst39*gconst39))),-1); |
| if(!x1540.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1539.value)+(((1.5707963267949)*(x1540.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1541=IKcos(j0); |
| IkReal x1542=IKsin(j0); |
| IkReal x1543=((1.0)*gconst39); |
| IkReal x1544=(gconst38*x1541); |
| IkReal x1545=((1.0)*x1542); |
| IkReal x1546=(((x1541*x1543))+((gconst38*x1545))); |
| evalcond[0]=((((-1.0)*x1544))+((gconst39*x1542))); |
| evalcond[1]=(((new_r11*x1541))+gconst38+(((-1.0)*new_r01*x1545))); |
| evalcond[2]=(x1544+(((-1.0)*x1542*x1543))+new_r11); |
| evalcond[3]=((-1.0)*x1546); |
| evalcond[4]=(((new_r01*x1541))+((new_r11*x1542))+(((-1.0)*x1543))); |
| evalcond[5]=(new_r01+(((-1.0)*x1546))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1547 = IKatan2WithCheck(IkReal((gconst38*gconst39)),IkReal(gconst39*gconst39),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1547.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1548=IKPowWithIntegerCheck(IKsign((((gconst39*new_r01))+((gconst38*new_r11)))),-1); |
| if(!x1548.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1547.value)+(((1.5707963267949)*(x1548.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1549=IKcos(j0); |
| IkReal x1550=IKsin(j0); |
| IkReal x1551=((1.0)*gconst39); |
| IkReal x1552=(gconst38*x1549); |
| IkReal x1553=((1.0)*x1550); |
| IkReal x1554=(((x1549*x1551))+((gconst38*x1553))); |
| evalcond[0]=((((-1.0)*x1552))+((gconst39*x1550))); |
| evalcond[1]=(((new_r11*x1549))+gconst38+(((-1.0)*new_r01*x1553))); |
| evalcond[2]=(x1552+(((-1.0)*x1550*x1551))+new_r11); |
| evalcond[3]=((-1.0)*x1554); |
| evalcond[4]=(((new_r01*x1549))+((new_r11*x1550))+(((-1.0)*x1551))); |
| evalcond[5]=((((-1.0)*x1554))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1555=IKPowWithIntegerCheck(gconst38,-1); |
| if(!x1555.valid){ |
| continue; |
| } |
| cj0array[0]=(new_r00*(x1555.value)); |
| if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| { |
| j0valid[0] = j0valid[1] = true; |
| j0array[0] = IKacos(cj0array[0]); |
| sj0array[0] = IKsin(j0array[0]); |
| cj0array[1] = cj0array[0]; |
| j0array[1] = -j0array[0]; |
| sj0array[1] = -sj0array[0]; |
| } |
| else if( isnan(cj0array[0]) ) |
| { |
| // probably any value will work |
| j0valid[0] = true; |
| cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| } |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[6]; |
| IkReal x1556=IKsin(j0); |
| IkReal x1557=IKcos(j0); |
| evalcond[0]=(new_r00*x1556); |
| evalcond[1]=(new_r11*x1556); |
| evalcond[2]=((-1.0)*gconst38*x1556); |
| evalcond[3]=(gconst38+((new_r11*x1557))); |
| evalcond[4]=(new_r11+((gconst38*x1557))); |
| evalcond[5]=(((new_r00*x1557))+(((-1.0)*gconst38))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=IKabs(new_r11); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1559 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1559.valid){ |
| continue; |
| } |
| IkReal x1558=((1.0)*(x1559.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1558))); |
| new_r11=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1558))); |
| IkReal gconst38=0; |
| IkReal x1560 = new_r01*new_r01; |
| if(IKabs(x1560)==0){ |
| continue; |
| } |
| IkReal gconst39=((1.0)*new_r01*(pow(x1560,-0.5))); |
| j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1562 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1562.valid){ |
| continue; |
| } |
| IkReal x1561=((1.0)*(x1562.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1561))); |
| new_r11=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1561))); |
| IkReal gconst38=0; |
| IkReal x1563 = new_r01*new_r01; |
| if(IKabs(x1563)==0){ |
| continue; |
| } |
| IkReal gconst39=((1.0)*new_r01*(pow(x1563,-0.5))); |
| j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1565 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1565.valid){ |
| continue; |
| } |
| IkReal x1564=((1.0)*(x1565.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1564))); |
| new_r11=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1564))); |
| IkReal gconst38=0; |
| IkReal x1566 = new_r01*new_r01; |
| if(IKabs(x1566)==0){ |
| continue; |
| } |
| IkReal gconst39=((1.0)*new_r01*(pow(x1566,-0.5))); |
| j0eval[0]=new_r01; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1567=IKPowWithIntegerCheck(gconst39,-1); |
| if(!x1567.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1568=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x1568.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*new_r00*(x1567.value)), (gconst39*(x1568.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1569=IKsin(j0); |
| IkReal x1570=IKcos(j0); |
| IkReal x1571=((1.0)*x1570); |
| IkReal x1572=(gconst39*x1571); |
| IkReal x1573=((-1.0)*x1569); |
| evalcond[0]=(new_r01*x1573); |
| evalcond[1]=(gconst39*x1573); |
| evalcond[2]=(((gconst39*x1569))+new_r00); |
| evalcond[3]=(new_r01+(((-1.0)*x1572))); |
| evalcond[4]=(new_r10+(((-1.0)*x1572))); |
| evalcond[5]=(((new_r01*x1570))+(((-1.0)*gconst39))); |
| evalcond[6]=(((new_r00*x1570))+((new_r10*x1569))); |
| evalcond[7]=(((new_r00*x1569))+(((-1.0)*new_r10*x1571))+gconst39); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1574 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1574.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1575=IKPowWithIntegerCheck(IKsign(gconst39),-1); |
| if(!x1575.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1574.value)+(((1.5707963267949)*(x1575.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1576=IKsin(j0); |
| IkReal x1577=IKcos(j0); |
| IkReal x1578=((1.0)*x1577); |
| IkReal x1579=(gconst39*x1578); |
| IkReal x1580=((-1.0)*x1576); |
| evalcond[0]=(new_r01*x1580); |
| evalcond[1]=(gconst39*x1580); |
| evalcond[2]=(((gconst39*x1576))+new_r00); |
| evalcond[3]=(new_r01+(((-1.0)*x1579))); |
| evalcond[4]=(new_r10+(((-1.0)*x1579))); |
| evalcond[5]=(((new_r01*x1577))+(((-1.0)*gconst39))); |
| evalcond[6]=(((new_r00*x1577))+((new_r10*x1576))); |
| evalcond[7]=(((new_r00*x1576))+(((-1.0)*new_r10*x1578))+gconst39); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1581 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1581.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1582=IKPowWithIntegerCheck(IKsign(gconst39),-1); |
| if(!x1582.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1581.value)+(((1.5707963267949)*(x1582.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1583=IKsin(j0); |
| IkReal x1584=IKcos(j0); |
| IkReal x1585=((1.0)*x1584); |
| IkReal x1586=(gconst39*x1585); |
| IkReal x1587=((-1.0)*x1583); |
| evalcond[0]=(new_r01*x1587); |
| evalcond[1]=(gconst39*x1587); |
| evalcond[2]=(((gconst39*x1583))+new_r00); |
| evalcond[3]=((((-1.0)*x1586))+new_r01); |
| evalcond[4]=((((-1.0)*x1586))+new_r10); |
| evalcond[5]=(((new_r01*x1584))+(((-1.0)*gconst39))); |
| evalcond[6]=(((new_r10*x1583))+((new_r00*x1584))); |
| evalcond[7]=(((new_r00*x1583))+(((-1.0)*new_r10*x1585))+gconst39); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1589 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1589.valid){ |
| continue; |
| } |
| IkReal x1588=((1.0)*(x1589.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1588))); |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1588))); |
| IkReal x1590 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x1590)==0){ |
| continue; |
| } |
| IkReal gconst38=((1.0)*new_r11*(pow(x1590,-0.5))); |
| IkReal gconst39=0; |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| CheckValue<IkReal> x1592 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1592.valid){ |
| continue; |
| } |
| IkReal x1591=((1.0)*(x1592.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1591))); |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1591))); |
| IkReal x1593 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x1593)==0){ |
| continue; |
| } |
| IkReal gconst38=((1.0)*new_r11*(pow(x1593,-0.5))); |
| IkReal gconst39=0; |
| j0eval[0]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| CheckValue<IkReal> x1595 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1595.valid){ |
| continue; |
| } |
| IkReal x1594=((1.0)*(x1595.value)); |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| sj2=gconst38; |
| cj2=gconst39; |
| j2=((3.14159265)+(((-1.0)*x1594))); |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| IkReal gconst37=((3.14159265358979)+(((-1.0)*x1594))); |
| IkReal x1596 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| if(IKabs(x1596)==0){ |
| continue; |
| } |
| IkReal gconst38=((1.0)*new_r11*(pow(x1596,-0.5))); |
| IkReal gconst39=0; |
| j0eval[0]=new_r10; |
| j0eval[1]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // 3 cases reached |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1597=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x1597.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1598=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1598.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((gconst38*(x1597.value)), ((-1.0)*gconst38*(x1598.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1599=IKcos(j0); |
| IkReal x1600=IKsin(j0); |
| IkReal x1601=(gconst38*x1600); |
| IkReal x1602=(gconst38*x1599); |
| evalcond[0]=(new_r11*x1600); |
| evalcond[1]=((-1.0)*new_r10*x1599); |
| evalcond[2]=((-1.0)*x1602); |
| evalcond[3]=((-1.0)*x1601); |
| evalcond[4]=(((new_r11*x1599))+gconst38); |
| evalcond[5]=(x1602+new_r11); |
| evalcond[6]=((((-1.0)*x1601))+new_r10); |
| evalcond[7]=(((new_r10*x1600))+(((-1.0)*gconst38))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1603=IKPowWithIntegerCheck(gconst38,-1); |
| if(!x1603.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1604=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1604.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((new_r10*(x1603.value)), ((-1.0)*gconst38*(x1604.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1605=IKcos(j0); |
| IkReal x1606=IKsin(j0); |
| IkReal x1607=(gconst38*x1606); |
| IkReal x1608=(gconst38*x1605); |
| evalcond[0]=(new_r11*x1606); |
| evalcond[1]=((-1.0)*new_r10*x1605); |
| evalcond[2]=((-1.0)*x1608); |
| evalcond[3]=((-1.0)*x1607); |
| evalcond[4]=(gconst38+((new_r11*x1605))); |
| evalcond[5]=(x1608+new_r11); |
| evalcond[6]=((((-1.0)*x1607))+new_r10); |
| evalcond[7]=(((new_r10*x1606))+(((-1.0)*gconst38))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1609 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1609.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1610=IKPowWithIntegerCheck(IKsign(gconst38),-1); |
| if(!x1610.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1609.value)+(((1.5707963267949)*(x1610.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1611=IKcos(j0); |
| IkReal x1612=IKsin(j0); |
| IkReal x1613=(gconst38*x1612); |
| IkReal x1614=(gconst38*x1611); |
| evalcond[0]=(new_r11*x1612); |
| evalcond[1]=((-1.0)*new_r10*x1611); |
| evalcond[2]=((-1.0)*x1614); |
| evalcond[3]=((-1.0)*x1613); |
| evalcond[4]=(((new_r11*x1611))+gconst38); |
| evalcond[5]=(x1614+new_r11); |
| evalcond[6]=((((-1.0)*x1613))+new_r10); |
| evalcond[7]=(((new_r10*x1612))+(((-1.0)*gconst38))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1615 = IKatan2WithCheck(IkReal((((gconst38*new_r00))+((gconst38*new_r11)))),IkReal(((((-1.0)*gconst38*new_r10))+((gconst38*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1615.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1616=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| if(!x1616.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1615.value)+(((1.5707963267949)*(x1616.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1617=IKsin(j0); |
| IkReal x1618=IKcos(j0); |
| IkReal x1619=((1.0)*gconst39); |
| IkReal x1620=((1.0)*gconst38); |
| IkReal x1621=((1.0)*x1618); |
| IkReal x1622=(((x1617*x1620))+((x1618*x1619))); |
| evalcond[0]=(((new_r11*x1618))+(((-1.0)*new_r01*x1617))+gconst38); |
| evalcond[1]=((((-1.0)*new_r10*x1621))+gconst39+((new_r00*x1617))); |
| evalcond[2]=(((gconst39*x1617))+new_r00+(((-1.0)*x1618*x1620))); |
| evalcond[3]=(((gconst38*x1618))+(((-1.0)*x1617*x1619))+new_r11); |
| evalcond[4]=(((new_r10*x1617))+(((-1.0)*x1620))+((new_r00*x1618))); |
| evalcond[5]=(((new_r11*x1617))+(((-1.0)*x1619))+((new_r01*x1618))); |
| evalcond[6]=((((-1.0)*x1622))+new_r01); |
| evalcond[7]=((((-1.0)*x1622))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1623=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst38*new_r00))+((gconst39*new_r10)))),-1); |
| if(!x1623.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1624 = IKatan2WithCheck(IkReal((((new_r10*new_r11))+((gconst38*gconst39)))),IkReal((((new_r00*new_r11))+(gconst39*gconst39))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1624.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1623.value)))+(x1624.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1625=IKsin(j0); |
| IkReal x1626=IKcos(j0); |
| IkReal x1627=((1.0)*gconst39); |
| IkReal x1628=((1.0)*gconst38); |
| IkReal x1629=((1.0)*x1626); |
| IkReal x1630=(((x1626*x1627))+((x1625*x1628))); |
| evalcond[0]=(((new_r11*x1626))+(((-1.0)*new_r01*x1625))+gconst38); |
| evalcond[1]=((((-1.0)*new_r10*x1629))+gconst39+((new_r00*x1625))); |
| evalcond[2]=(((gconst39*x1625))+new_r00+(((-1.0)*x1626*x1628))); |
| evalcond[3]=(((gconst38*x1626))+(((-1.0)*x1625*x1627))+new_r11); |
| evalcond[4]=(((new_r10*x1625))+(((-1.0)*x1628))+((new_r00*x1626))); |
| evalcond[5]=(((new_r11*x1625))+((new_r01*x1626))+(((-1.0)*x1627))); |
| evalcond[6]=((((-1.0)*x1630))+new_r01); |
| evalcond[7]=((((-1.0)*x1630))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1631 = IKatan2WithCheck(IkReal((((gconst39*new_r11))+((gconst38*new_r10)))),IkReal((((gconst39*new_r01))+((gconst38*new_r00)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1631.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1632=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| if(!x1632.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1631.value)+(((1.5707963267949)*(x1632.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1633=IKsin(j0); |
| IkReal x1634=IKcos(j0); |
| IkReal x1635=((1.0)*gconst39); |
| IkReal x1636=((1.0)*gconst38); |
| IkReal x1637=((1.0)*x1634); |
| IkReal x1638=(((x1634*x1635))+((x1633*x1636))); |
| evalcond[0]=(((new_r11*x1634))+gconst38+(((-1.0)*new_r01*x1633))); |
| evalcond[1]=(gconst39+((new_r00*x1633))+(((-1.0)*new_r10*x1637))); |
| evalcond[2]=((((-1.0)*x1634*x1636))+((gconst39*x1633))+new_r00); |
| evalcond[3]=((((-1.0)*x1633*x1635))+((gconst38*x1634))+new_r11); |
| evalcond[4]=(((new_r10*x1633))+(((-1.0)*x1636))+((new_r00*x1634))); |
| evalcond[5]=(((new_r11*x1633))+(((-1.0)*x1635))+((new_r01*x1634))); |
| evalcond[6]=((((-1.0)*x1638))+new_r01); |
| evalcond[7]=((((-1.0)*x1638))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| new_r11=0; |
| new_r01=0; |
| new_r22=0; |
| new_r20=0; |
| j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j0] |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1640 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1640.valid){ |
| continue; |
| } |
| IkReal x1639=x1640.value; |
| j0array[0]=((-1.0)*x1639); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| j0array[1]=((3.14159265358979)+(((-1.0)*x1639))); |
| sj0array[1]=IKsin(j0array[1]); |
| cj0array[1]=IKcos(j0array[1]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| if( j0array[1] > IKPI ) |
| { |
| j0array[1]-=IK2PI; |
| } |
| else if( j0array[1] < -IKPI ) |
| { j0array[1]+=IK2PI; |
| } |
| j0valid[1] = true; |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[1]; |
| evalcond[0]=(((new_r00*(IKsin(j0))))+(((-1.0)*new_r10*(IKcos(j0))))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| j0eval[0]=new_r00; |
| j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| j0eval[2]=IKsign(new_r00); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| j0eval[0]=new_r01; |
| j0eval[1]=new_r00; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| new_r11=0; |
| new_r10=0; |
| new_r22=0; |
| new_r02=0; |
| j0eval[0]=new_r00; |
| j0eval[1]=sj2; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[1]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j2))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(((-1.0)*new_r00), new_r01); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1641=IKsin(j0); |
| IkReal x1642=IKcos(j0); |
| IkReal x1643=((-1.0)*x1641); |
| evalcond[0]=(new_r00*x1642); |
| evalcond[1]=(x1641+new_r00); |
| evalcond[2]=x1643; |
| evalcond[3]=((-1.0)*x1642); |
| evalcond[4]=(new_r01*x1643); |
| evalcond[5]=((1.0)+((new_r00*x1641))); |
| evalcond[6]=((-1.0)+((new_r01*x1642))); |
| evalcond[7]=((((-1.0)*x1642))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j2)))), 6.28318530717959))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| 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 ) |
| continue; |
| j0array[0]=IKatan2(new_r00, ((-1.0)*new_r01)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1644=IKcos(j0); |
| IkReal x1645=IKsin(j0); |
| evalcond[0]=x1645; |
| evalcond[1]=x1644; |
| evalcond[2]=(new_r00*x1644); |
| evalcond[3]=(x1644+new_r01); |
| evalcond[4]=((-1.0)*new_r01*x1645); |
| evalcond[5]=((-1.0)+((new_r00*x1645))); |
| evalcond[6]=((1.0)+((new_r01*x1644))); |
| evalcond[7]=((((-1.0)*x1645))+new_r00); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1648=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1648.valid){ |
| continue; |
| } |
| IkReal x1646=x1648.value; |
| IkReal x1647=((-1.0)*x1646); |
| CheckValue<IkReal> x1649=IKPowWithIntegerCheck(sj2,-1); |
| if(!x1649.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((cj2*x1647), (x1647*(cj2*cj2)*(x1649.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1650=IKsin(j0); |
| IkReal x1651=IKcos(j0); |
| IkReal x1652=((1.0)*sj2); |
| IkReal x1653=((1.0)*cj2); |
| IkReal x1654=(cj2*x1650); |
| IkReal x1655=(((x1650*x1652))+((x1651*x1653))); |
| evalcond[0]=(cj2+((new_r00*x1650))); |
| evalcond[1]=(sj2+(((-1.0)*new_r01*x1650))); |
| evalcond[2]=((((-1.0)*x1652))+((new_r00*x1651))); |
| evalcond[3]=((((-1.0)*x1653))+((new_r01*x1651))); |
| evalcond[4]=((((-1.0)*x1650*x1653))+((sj2*x1651))); |
| evalcond[5]=(x1654+new_r00+(((-1.0)*x1651*x1652))); |
| evalcond[6]=((-1.0)*x1655); |
| evalcond[7]=((((-1.0)*x1655))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1656=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x1656.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1657=IKPowWithIntegerCheck(new_r00,-1); |
| if(!x1657.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((sj2*(x1656.value)), (sj2*(x1657.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1658=IKsin(j0); |
| IkReal x1659=IKcos(j0); |
| IkReal x1660=((1.0)*sj2); |
| IkReal x1661=((1.0)*cj2); |
| IkReal x1662=(cj2*x1658); |
| IkReal x1663=(((x1658*x1660))+((x1659*x1661))); |
| evalcond[0]=(cj2+((new_r00*x1658))); |
| evalcond[1]=(sj2+(((-1.0)*new_r01*x1658))); |
| evalcond[2]=(((new_r00*x1659))+(((-1.0)*x1660))); |
| evalcond[3]=((((-1.0)*x1661))+((new_r01*x1659))); |
| evalcond[4]=(((sj2*x1659))+(((-1.0)*x1658*x1661))); |
| evalcond[5]=(x1662+new_r00+(((-1.0)*x1659*x1660))); |
| evalcond[6]=((-1.0)*x1663); |
| evalcond[7]=((((-1.0)*x1663))+new_r01); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1664=IKPowWithIntegerCheck(IKsign(new_r00),-1); |
| if(!x1664.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1665 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(sj2),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1665.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1664.value)))+(x1665.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1666=IKsin(j0); |
| IkReal x1667=IKcos(j0); |
| IkReal x1668=((1.0)*sj2); |
| IkReal x1669=((1.0)*cj2); |
| IkReal x1670=(cj2*x1666); |
| IkReal x1671=(((x1667*x1669))+((x1666*x1668))); |
| evalcond[0]=(cj2+((new_r00*x1666))); |
| evalcond[1]=(sj2+(((-1.0)*new_r01*x1666))); |
| evalcond[2]=((((-1.0)*x1668))+((new_r00*x1667))); |
| evalcond[3]=(((new_r01*x1667))+(((-1.0)*x1669))); |
| evalcond[4]=(((sj2*x1667))+(((-1.0)*x1666*x1669))); |
| evalcond[5]=(x1670+(((-1.0)*x1667*x1668))+new_r00); |
| evalcond[6]=((-1.0)*x1671); |
| evalcond[7]=(new_r01+(((-1.0)*x1671))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[3]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| j0eval[0]=new_r10; |
| j0eval[1]=IKsign(new_r10); |
| j0eval[2]=((IKabs(cj2))+(IKabs(sj2))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[3]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| j0eval[0]=new_r11; |
| j0eval[1]=IKsign(new_r11); |
| j0eval[2]=((IKabs(cj2))+(IKabs(sj2))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[2]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| new_r00=0; |
| new_r01=0; |
| new_r12=0; |
| new_r22=0; |
| j0eval[0]=new_r10; |
| j0eval[1]=new_r11; |
| if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j0] |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1672=IKPowWithIntegerCheck(new_r10,-1); |
| if(!x1672.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1673=IKPowWithIntegerCheck(new_r11,-1); |
| if(!x1673.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((sj2*(x1672.value)), ((-1.0)*sj2*(x1673.value))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1674=IKcos(j0); |
| IkReal x1675=IKsin(j0); |
| IkReal x1676=((1.0)*sj2); |
| IkReal x1677=(sj2*x1674); |
| IkReal x1678=((1.0)*x1674); |
| IkReal x1679=(cj2*x1675); |
| IkReal x1680=(((x1675*x1676))+((cj2*x1678))); |
| evalcond[0]=(sj2+((new_r11*x1674))); |
| evalcond[1]=(cj2+(((-1.0)*new_r10*x1678))); |
| evalcond[2]=(((new_r10*x1675))+(((-1.0)*x1676))); |
| evalcond[3]=(((new_r11*x1675))+(((-1.0)*cj2))); |
| evalcond[4]=(x1679+(((-1.0)*x1674*x1676))); |
| evalcond[5]=(x1677+(((-1.0)*x1679))+new_r11); |
| evalcond[6]=((-1.0)*x1680); |
| evalcond[7]=((((-1.0)*x1680))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1681=IKPowWithIntegerCheck(IKsign(new_r11),-1); |
| if(!x1681.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1682 = IKatan2WithCheck(IkReal(cj2),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1682.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1681.value)))+(x1682.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1683=IKcos(j0); |
| IkReal x1684=IKsin(j0); |
| IkReal x1685=((1.0)*sj2); |
| IkReal x1686=(sj2*x1683); |
| IkReal x1687=((1.0)*x1683); |
| IkReal x1688=(cj2*x1684); |
| IkReal x1689=(((x1684*x1685))+((cj2*x1687))); |
| evalcond[0]=(sj2+((new_r11*x1683))); |
| evalcond[1]=(cj2+(((-1.0)*new_r10*x1687))); |
| evalcond[2]=((((-1.0)*x1685))+((new_r10*x1684))); |
| evalcond[3]=(((new_r11*x1684))+(((-1.0)*cj2))); |
| evalcond[4]=(x1688+(((-1.0)*x1683*x1685))); |
| evalcond[5]=(x1686+(((-1.0)*x1688))+new_r11); |
| evalcond[6]=((-1.0)*x1689); |
| evalcond[7]=((((-1.0)*x1689))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1690=IKPowWithIntegerCheck(IKsign(new_r10),-1); |
| if(!x1690.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1691 = IKatan2WithCheck(IkReal(sj2),IkReal(cj2),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1691.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1690.value)))+(x1691.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1692=IKcos(j0); |
| IkReal x1693=IKsin(j0); |
| IkReal x1694=((1.0)*sj2); |
| IkReal x1695=(sj2*x1692); |
| IkReal x1696=((1.0)*x1692); |
| IkReal x1697=(cj2*x1693); |
| IkReal x1698=(((x1693*x1694))+((cj2*x1696))); |
| evalcond[0]=(sj2+((new_r11*x1692))); |
| evalcond[1]=(cj2+(((-1.0)*new_r10*x1696))); |
| evalcond[2]=((((-1.0)*x1694))+((new_r10*x1693))); |
| evalcond[3]=(((new_r11*x1693))+(((-1.0)*cj2))); |
| evalcond[4]=((((-1.0)*x1692*x1694))+x1697); |
| evalcond[5]=(x1695+(((-1.0)*x1697))+new_r11); |
| evalcond[6]=((-1.0)*x1698); |
| evalcond[7]=((((-1.0)*x1698))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| sj1=-1.0; |
| cj1=0; |
| j1=-1.5707963267949; |
| new_r00=0; |
| new_r10=0; |
| new_r21=0; |
| new_r22=0; |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j0] |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1700 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1700.valid){ |
| continue; |
| } |
| IkReal x1699=x1700.value; |
| j0array[0]=((-1.0)*x1699); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| j0array[1]=((3.14159265358979)+(((-1.0)*x1699))); |
| sj0array[1]=IKsin(j0array[1]); |
| cj0array[1]=IKcos(j0array[1]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| if( j0array[1] > IKPI ) |
| { |
| j0array[1]-=IK2PI; |
| } |
| else if( j0array[1] < -IKPI ) |
| { j0array[1]+=IK2PI; |
| } |
| j0valid[1] = true; |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[1]; |
| evalcond[0]=(((new_r11*(IKcos(j0))))+(((-1.0)*new_r01*(IKsin(j0))))); |
| if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x1701=((1.0)*new_r00); |
| CheckValue<IkReal> x1702=IKPowWithIntegerCheck(IKsign(((((-1.0)*sj2*x1701))+((cj2*new_r10)))),-1); |
| if(!x1702.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1703 = IKatan2WithCheck(IkReal((((cj2*sj2))+(((-1.0)*new_r10*x1701)))),IkReal(((cj2*cj2)+(((-1.0)*new_r00*x1701)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1703.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1702.value)))+(x1703.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1704=IKsin(j0); |
| IkReal x1705=IKcos(j0); |
| IkReal x1706=((1.0)*sj2); |
| IkReal x1707=(sj2*x1705); |
| IkReal x1708=((1.0)*x1705); |
| IkReal x1709=(cj2*x1704); |
| IkReal x1710=(((x1704*x1706))+((cj2*x1708))); |
| evalcond[0]=(sj2+(((-1.0)*new_r01*x1704))+((new_r11*x1705))); |
| evalcond[1]=(cj2+((new_r00*x1704))+(((-1.0)*new_r10*x1708))); |
| evalcond[2]=(x1709+(((-1.0)*x1705*x1706))+new_r00); |
| evalcond[3]=(x1707+(((-1.0)*x1709))+new_r11); |
| evalcond[4]=(((new_r00*x1705))+(((-1.0)*x1706))+((new_r10*x1704))); |
| evalcond[5]=(((new_r01*x1705))+((new_r11*x1704))+(((-1.0)*cj2))); |
| evalcond[6]=((((-1.0)*x1710))+new_r01); |
| evalcond[7]=((((-1.0)*x1710))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| IkReal x1711=((1.0)*sj2); |
| 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); |
| if(!x1712.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1713=IKPowWithIntegerCheck(IKsign((((cj2*new_r11))+(((-1.0)*new_r01*x1711)))),-1); |
| if(!x1713.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1712.value)+(((1.5707963267949)*(x1713.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1714=IKsin(j0); |
| IkReal x1715=IKcos(j0); |
| IkReal x1716=((1.0)*sj2); |
| IkReal x1717=(sj2*x1715); |
| IkReal x1718=((1.0)*x1715); |
| IkReal x1719=(cj2*x1714); |
| IkReal x1720=(((x1714*x1716))+((cj2*x1718))); |
| evalcond[0]=(((new_r11*x1715))+sj2+(((-1.0)*new_r01*x1714))); |
| evalcond[1]=(cj2+((new_r00*x1714))+(((-1.0)*new_r10*x1718))); |
| evalcond[2]=(x1719+(((-1.0)*x1715*x1716))+new_r00); |
| evalcond[3]=(x1717+(((-1.0)*x1719))+new_r11); |
| evalcond[4]=(((new_r10*x1714))+(((-1.0)*x1716))+((new_r00*x1715))); |
| evalcond[5]=(((new_r11*x1714))+((new_r01*x1715))+(((-1.0)*cj2))); |
| evalcond[6]=(new_r01+(((-1.0)*x1720))); |
| evalcond[7]=(new_r10+(((-1.0)*x1720))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1721 = IKatan2WithCheck(IkReal((((new_r10*sj2))+((cj2*new_r11)))),IkReal((((new_r00*sj2))+((cj2*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1721.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1722=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| if(!x1722.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(x1721.value)+(((1.5707963267949)*(x1722.value)))); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1723=IKsin(j0); |
| IkReal x1724=IKcos(j0); |
| IkReal x1725=((1.0)*sj2); |
| IkReal x1726=(sj2*x1724); |
| IkReal x1727=((1.0)*x1724); |
| IkReal x1728=(cj2*x1723); |
| IkReal x1729=(((x1723*x1725))+((cj2*x1727))); |
| evalcond[0]=(sj2+((new_r11*x1724))+(((-1.0)*new_r01*x1723))); |
| evalcond[1]=(cj2+(((-1.0)*new_r10*x1727))+((new_r00*x1723))); |
| evalcond[2]=(x1728+(((-1.0)*x1724*x1725))+new_r00); |
| evalcond[3]=(x1726+new_r11+(((-1.0)*x1728))); |
| evalcond[4]=(((new_r10*x1723))+(((-1.0)*x1725))+((new_r00*x1724))); |
| evalcond[5]=(((new_r11*x1723))+(((-1.0)*cj2))+((new_r01*x1724))); |
| evalcond[6]=(new_r01+(((-1.0)*x1729))); |
| evalcond[7]=(new_r10+(((-1.0)*x1729))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j0eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j0eval[1]; |
| new_r02=0; |
| new_r12=0; |
| new_r20=0; |
| new_r21=0; |
| j0eval[0]=((IKabs((new_r10*new_r22)))+(IKabs((new_r00*new_r22)))); |
| if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| { |
| continue; // no branches [j0] |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| IkReal x1730=((-1.0)*new_r22); |
| CheckValue<IkReal> x1732 = IKatan2WithCheck(IkReal((new_r00*x1730)),IkReal((new_r10*x1730)),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1732.valid){ |
| continue; |
| } |
| IkReal x1731=x1732.value; |
| j0array[0]=((-1.0)*x1731); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| j0array[1]=((3.14159265358979)+(((-1.0)*x1731))); |
| sj0array[1]=IKsin(j0array[1]); |
| cj0array[1]=IKcos(j0array[1]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| if( j0array[1] > IKPI ) |
| { |
| j0array[1]-=IK2PI; |
| } |
| else if( j0array[1] < -IKPI ) |
| { j0array[1]+=IK2PI; |
| } |
| j0valid[1] = true; |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[5]; |
| IkReal x1733=IKsin(j0); |
| IkReal x1734=IKcos(j0); |
| IkReal x1735=((1.0)*x1734); |
| IkReal x1736=(new_r11*x1733); |
| evalcond[0]=(((new_r10*x1733))+((new_r00*x1734))); |
| evalcond[1]=(x1736+((new_r01*x1734))); |
| evalcond[2]=(((new_r11*x1734))+(((-1.0)*new_r01*x1733))); |
| evalcond[3]=((((-1.0)*new_r10*x1735))+((new_r00*x1733))); |
| evalcond[4]=((((-1.0)*new_r22*x1736))+(((-1.0)*new_r01*new_r22*x1735))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1738 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1738.valid){ |
| continue; |
| } |
| IkReal x1737=x1738.value; |
| j0array[0]=((-1.0)*x1737); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| j0array[1]=((3.14159265358979)+(((-1.0)*x1737))); |
| sj0array[1]=IKsin(j0array[1]); |
| cj0array[1]=IKcos(j0array[1]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| if( j0array[1] > IKPI ) |
| { |
| j0array[1]-=IK2PI; |
| } |
| else if( j0array[1] < -IKPI ) |
| { j0array[1]+=IK2PI; |
| } |
| j0valid[1] = true; |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[5]; |
| IkReal x1739=IKcos(j0); |
| IkReal x1740=IKsin(j0); |
| IkReal x1741=((1.0)*new_r22); |
| IkReal x1742=(new_r10*x1740); |
| IkReal x1743=(new_r00*x1739); |
| evalcond[0]=(x1742+x1743); |
| evalcond[1]=(((new_r11*x1739))+(((-1.0)*new_r01*x1740))); |
| evalcond[2]=(((new_r00*x1740))+(((-1.0)*new_r10*x1739))); |
| evalcond[3]=((((-1.0)*x1741*x1742))+(((-1.0)*x1741*x1743))); |
| evalcond[4]=((((-1.0)*new_r11*x1740*x1741))+(((-1.0)*new_r01*x1739*x1741))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[2], cj0array[2], sj0array[2]; |
| bool j0valid[2]={false}; |
| _nj0 = 2; |
| CheckValue<IkReal> x1745 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1745.valid){ |
| continue; |
| } |
| IkReal x1744=x1745.value; |
| j0array[0]=((-1.0)*x1744); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| j0array[1]=((3.14159265358979)+(((-1.0)*x1744))); |
| sj0array[1]=IKsin(j0array[1]); |
| cj0array[1]=IKcos(j0array[1]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| if( j0array[1] > IKPI ) |
| { |
| j0array[1]-=IK2PI; |
| } |
| else if( j0array[1] < -IKPI ) |
| { j0array[1]+=IK2PI; |
| } |
| j0valid[1] = true; |
| for(int ij0 = 0; ij0 < 2; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[5]; |
| IkReal x1746=IKcos(j0); |
| IkReal x1747=IKsin(j0); |
| IkReal x1748=((1.0)*new_r10); |
| IkReal x1749=((1.0)*new_r01); |
| IkReal x1750=(new_r22*x1747); |
| IkReal x1751=(new_r22*x1746); |
| evalcond[0]=(((new_r01*x1746))+((new_r11*x1747))); |
| evalcond[1]=((((-1.0)*x1747*x1749))+((new_r11*x1746))); |
| evalcond[2]=((((-1.0)*x1746*x1748))+((new_r00*x1747))); |
| evalcond[3]=((((-1.0)*x1748*x1750))+(((-1.0)*new_r00*x1751))); |
| evalcond[4]=((((-1.0)*x1749*x1751))+(((-1.0)*new_r11*x1750))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j0] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1753=IKPowWithIntegerCheck(cj1,-1); |
| if(!x1753.valid){ |
| continue; |
| } |
| IkReal x1752=x1753.value; |
| CheckValue<IkReal> x1754=IKPowWithIntegerCheck(new_r01,-1); |
| if(!x1754.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j0array[0]=IKatan2((x1752*(x1754.value)*((((cj1*sj2))+((new_r02*new_r11))))), (new_r02*x1752)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[18]; |
| IkReal x1755=IKcos(j0); |
| IkReal x1756=IKsin(j0); |
| IkReal x1757=(sj1*sj2); |
| IkReal x1758=((1.0)*sj1); |
| IkReal x1759=(cj2*sj1); |
| IkReal x1760=((1.0)*cj1); |
| IkReal x1761=((1.0)*cj2); |
| IkReal x1762=(new_r10*x1756); |
| IkReal x1763=(new_r01*x1755); |
| IkReal x1764=(new_r00*x1755); |
| IkReal x1765=((1.0)*x1756); |
| IkReal x1766=(new_r11*x1756); |
| IkReal x1767=(new_r12*x1756); |
| IkReal x1768=(new_r02*x1755); |
| evalcond[0]=((((-1.0)*x1755*x1760))+new_r02); |
| evalcond[1]=((((-1.0)*x1756*x1760))+new_r12); |
| evalcond[2]=((((-1.0)*new_r02*x1765))+((new_r12*x1755))); |
| evalcond[3]=(sj2+(((-1.0)*new_r01*x1765))+((new_r11*x1755))); |
| evalcond[4]=(cj2+((new_r00*x1756))+(((-1.0)*new_r10*x1755))); |
| evalcond[5]=(((cj2*x1756))+new_r00+((x1755*x1757))); |
| evalcond[6]=(((sj2*x1755))+new_r11+((x1756*x1759))); |
| evalcond[7]=((((-1.0)*x1760))+x1768+x1767); |
| evalcond[8]=(x1762+x1764+x1757); |
| evalcond[9]=(x1763+x1766+x1759); |
| evalcond[10]=((((-1.0)*sj2*x1765))+new_r01+((x1755*x1759))); |
| evalcond[11]=((((-1.0)*x1755*x1761))+new_r10+((x1756*x1757))); |
| evalcond[12]=(((new_r20*sj1))+((cj1*x1762))+((cj1*x1764))); |
| evalcond[13]=(((new_r21*sj1))+((cj1*x1763))+((cj1*x1766))); |
| evalcond[14]=((-1.0)+((new_r22*sj1))+((cj1*x1768))+((cj1*x1767))); |
| evalcond[15]=(((cj1*new_r22))+(((-1.0)*x1758*x1767))+(((-1.0)*x1758*x1768))); |
| evalcond[16]=((((-1.0)*sj2))+((cj1*new_r20))+(((-1.0)*x1758*x1764))+(((-1.0)*x1758*x1762))); |
| evalcond[17]=((((-1.0)*x1761))+((cj1*new_r21))+(((-1.0)*x1758*x1763))+(((-1.0)*x1758*x1766))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1769=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| if(!x1769.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1770 = IKatan2WithCheck(IkReal(new_r12),IkReal(new_r02),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1770.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1769.value)))+(x1770.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[18]; |
| IkReal x1771=IKcos(j0); |
| IkReal x1772=IKsin(j0); |
| IkReal x1773=(sj1*sj2); |
| IkReal x1774=((1.0)*sj1); |
| IkReal x1775=(cj2*sj1); |
| IkReal x1776=((1.0)*cj1); |
| IkReal x1777=((1.0)*cj2); |
| IkReal x1778=(new_r10*x1772); |
| IkReal x1779=(new_r01*x1771); |
| IkReal x1780=(new_r00*x1771); |
| IkReal x1781=((1.0)*x1772); |
| IkReal x1782=(new_r11*x1772); |
| IkReal x1783=(new_r12*x1772); |
| IkReal x1784=(new_r02*x1771); |
| evalcond[0]=((((-1.0)*x1771*x1776))+new_r02); |
| evalcond[1]=((((-1.0)*x1772*x1776))+new_r12); |
| evalcond[2]=((((-1.0)*new_r02*x1781))+((new_r12*x1771))); |
| evalcond[3]=(sj2+(((-1.0)*new_r01*x1781))+((new_r11*x1771))); |
| evalcond[4]=(cj2+((new_r00*x1772))+(((-1.0)*new_r10*x1771))); |
| evalcond[5]=(((x1771*x1773))+new_r00+((cj2*x1772))); |
| evalcond[6]=(((sj2*x1771))+new_r11+((x1772*x1775))); |
| evalcond[7]=(x1783+x1784+(((-1.0)*x1776))); |
| evalcond[8]=(x1780+x1773+x1778); |
| evalcond[9]=(x1782+x1775+x1779); |
| evalcond[10]=(((x1771*x1775))+new_r01+(((-1.0)*sj2*x1781))); |
| evalcond[11]=((((-1.0)*x1771*x1777))+new_r10+((x1772*x1773))); |
| evalcond[12]=(((new_r20*sj1))+((cj1*x1780))+((cj1*x1778))); |
| evalcond[13]=(((cj1*x1782))+((new_r21*sj1))+((cj1*x1779))); |
| evalcond[14]=((-1.0)+((cj1*x1784))+((cj1*x1783))+((new_r22*sj1))); |
| evalcond[15]=((((-1.0)*x1774*x1784))+(((-1.0)*x1774*x1783))+((cj1*new_r22))); |
| evalcond[16]=((((-1.0)*sj2))+(((-1.0)*x1774*x1780))+((cj1*new_r20))+(((-1.0)*x1774*x1778))); |
| evalcond[17]=((((-1.0)*x1774*x1782))+((cj1*new_r21))+(((-1.0)*x1777))+(((-1.0)*x1774*x1779))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j0array[1], cj0array[1], sj0array[1]; |
| bool j0valid[1]={false}; |
| _nj0 = 1; |
| CheckValue<IkReal> x1785=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| if(!x1785.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1786 = IKatan2WithCheck(IkReal(new_r12),IkReal(new_r02),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1786.valid){ |
| continue; |
| } |
| j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1785.value)))+(x1786.value)); |
| sj0array[0]=IKsin(j0array[0]); |
| cj0array[0]=IKcos(j0array[0]); |
| if( j0array[0] > IKPI ) |
| { |
| j0array[0]-=IK2PI; |
| } |
| else if( j0array[0] < -IKPI ) |
| { j0array[0]+=IK2PI; |
| } |
| j0valid[0] = true; |
| for(int ij0 = 0; ij0 < 1; ++ij0) |
| { |
| if( !j0valid[ij0] ) |
| { |
| continue; |
| } |
| _ij0[0] = ij0; _ij0[1] = -1; |
| for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| { |
| if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j0valid[iij0]=false; _ij0[1] = iij0; break; |
| } |
| } |
| j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1787=IKcos(j0); |
| IkReal x1788=IKsin(j0); |
| IkReal x1789=(cj1*x1787); |
| IkReal x1790=(cj1*x1788); |
| IkReal x1791=((1.0)*x1788); |
| IkReal x1792=(new_r02*x1787); |
| evalcond[0]=((((-1.0)*x1789))+new_r02); |
| evalcond[1]=((((-1.0)*x1790))+new_r12); |
| evalcond[2]=(((new_r12*x1787))+(((-1.0)*new_r02*x1791))); |
| evalcond[3]=(x1792+((new_r12*x1788))+(((-1.0)*cj1))); |
| evalcond[4]=(((new_r20*sj1))+((new_r10*x1790))+((new_r00*x1789))); |
| evalcond[5]=(((new_r11*x1790))+((new_r01*x1789))+((new_r21*sj1))); |
| evalcond[6]=((-1.0)+((new_r12*x1790))+((new_r22*sj1))+((new_r02*x1789))); |
| evalcond[7]=(((cj1*new_r22))+(((-1.0)*new_r12*sj1*x1791))+(((-1.0)*sj1*x1792))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| IkReal j2eval[3]; |
| j2eval[0]=cj1; |
| j2eval[1]=IKsign(cj1); |
| j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2eval[2]; |
| j2eval[0]=cj1; |
| j2eval[1]=sj0; |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal j2eval[3]; |
| j2eval[0]=cj1; |
| j2eval[1]=sj0; |
| j2eval[2]=sj1; |
| if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| { |
| { |
| IkReal evalcond[5]; |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r02; |
| evalcond[2]=new_r12; |
| evalcond[3]=new_r20; |
| evalcond[4]=new_r21; |
| 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 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| IkReal x1793=((1.0)*cj0); |
| 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 ) |
| continue; |
| j2array[0]=IKatan2((((new_r01*sj0))+(((-1.0)*new_r00*x1793))), ((((-1.0)*new_r01*x1793))+(((-1.0)*new_r00*sj0)))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1794=IKsin(j2); |
| IkReal x1795=IKcos(j2); |
| IkReal x1796=((1.0)*cj0); |
| IkReal x1797=(sj0*x1795); |
| IkReal x1798=(cj0*x1794); |
| IkReal x1799=(sj0*x1794); |
| IkReal x1800=(x1798+x1797); |
| evalcond[0]=(x1794+((new_r10*sj0))+((cj0*new_r00))); |
| evalcond[1]=(x1795+((new_r11*sj0))+((cj0*new_r01))); |
| evalcond[2]=((((-1.0)*new_r01*sj0))+x1794+((cj0*new_r11))); |
| evalcond[3]=((((-1.0)*new_r10*x1796))+x1795+((new_r00*sj0))); |
| evalcond[4]=(x1800+new_r00); |
| evalcond[5]=(x1800+new_r11); |
| evalcond[6]=((((-1.0)*x1799))+new_r01+((cj0*x1795))); |
| evalcond[7]=((((-1.0)*x1795*x1796))+x1799+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r02; |
| evalcond[2]=new_r12; |
| evalcond[3]=new_r20; |
| evalcond[4]=new_r21; |
| 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 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2((((new_r01*sj0))+((cj0*new_r00))), (((cj0*new_r01))+(((-1.0)*new_r00*sj0)))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1801=IKsin(j2); |
| IkReal x1802=IKcos(j2); |
| IkReal x1803=((1.0)*sj0); |
| IkReal x1804=((1.0)*cj0); |
| IkReal x1805=((1.0)*x1802); |
| IkReal x1806=(((x1802*x1804))+((x1801*x1803))); |
| evalcond[0]=((((-1.0)*new_r01*x1803))+x1801+((cj0*new_r11))); |
| evalcond[1]=(((new_r00*sj0))+x1802+(((-1.0)*new_r10*x1804))); |
| evalcond[2]=(((new_r10*sj0))+((cj0*new_r00))+(((-1.0)*x1801))); |
| evalcond[3]=(((new_r11*sj0))+(((-1.0)*x1805))+((cj0*new_r01))); |
| evalcond[4]=(((sj0*x1802))+(((-1.0)*x1801*x1804))+new_r00); |
| evalcond[5]=(((cj0*x1801))+(((-1.0)*x1802*x1803))+new_r11); |
| evalcond[6]=((((-1.0)*x1806))+new_r01); |
| evalcond[7]=((((-1.0)*x1806))+new_r10); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959))); |
| evalcond[1]=new_r12; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((-1.0)*new_r11), new_r10); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1807=IKsin(j2); |
| IkReal x1808=IKcos(j2); |
| IkReal x1809=((1.0)*sj1); |
| IkReal x1810=((1.0)*cj1); |
| evalcond[0]=(x1807+new_r11); |
| evalcond[1]=(x1808+(((-1.0)*new_r10))); |
| evalcond[2]=(((sj1*x1807))+new_r00); |
| evalcond[3]=(((sj1*x1808))+new_r01); |
| evalcond[4]=((((-1.0)*x1807*x1810))+new_r20); |
| evalcond[5]=((((-1.0)*x1808*x1810))+new_r21); |
| evalcond[6]=(((cj1*new_r20))+(((-1.0)*new_r00*x1809))+(((-1.0)*x1807))); |
| evalcond[7]=((((-1.0)*new_r01*x1809))+((cj1*new_r21))+(((-1.0)*x1808))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959))); |
| evalcond[1]=new_r12; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1811=IKsin(j2); |
| IkReal x1812=IKcos(j2); |
| IkReal x1813=((1.0)*cj1); |
| evalcond[0]=(x1812+new_r10); |
| evalcond[1]=(x1811+(((-1.0)*new_r11))); |
| evalcond[2]=((((-1.0)*x1811*x1813))+new_r20); |
| evalcond[3]=((((-1.0)*x1812*x1813))+new_r21); |
| evalcond[4]=(((sj1*x1811))+(((-1.0)*new_r00))); |
| evalcond[5]=(((sj1*x1812))+(((-1.0)*new_r01))); |
| evalcond[6]=(((cj1*new_r20))+((new_r00*sj1))+(((-1.0)*x1811))); |
| evalcond[7]=(((cj1*new_r21))+((new_r01*sj1))+(((-1.0)*x1812))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j1))), 6.28318530717959))); |
| evalcond[1]=new_r22; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH ) |
| continue; |
| j2array[0]=IKatan2(new_r20, new_r21); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1814=IKcos(j2); |
| IkReal x1815=IKsin(j2); |
| IkReal x1816=((1.0)*sj0); |
| IkReal x1817=((1.0)*x1814); |
| evalcond[0]=(new_r20+(((-1.0)*x1815))); |
| evalcond[1]=((((-1.0)*x1817))+new_r21); |
| evalcond[2]=(((sj0*x1814))+new_r00); |
| evalcond[3]=(((cj0*x1815))+new_r11); |
| evalcond[4]=((((-1.0)*x1815*x1816))+new_r01); |
| evalcond[5]=((((-1.0)*new_r02*x1817))+new_r10); |
| evalcond[6]=((((-1.0)*new_r01*x1816))+x1815+((cj0*new_r11))); |
| evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x1814); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j1)))), 6.28318530717959))); |
| evalcond[1]=new_r22; |
| if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| 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 ) |
| continue; |
| j2array[0]=IKatan2(((-1.0)*new_r20), ((-1.0)*new_r21)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[8]; |
| IkReal x1818=IKcos(j2); |
| IkReal x1819=IKsin(j2); |
| IkReal x1820=((1.0)*sj0); |
| evalcond[0]=(x1819+new_r20); |
| evalcond[1]=(x1818+new_r21); |
| evalcond[2]=(((sj0*x1818))+new_r00); |
| evalcond[3]=(((cj0*x1819))+new_r11); |
| evalcond[4]=(((new_r02*x1818))+new_r10); |
| evalcond[5]=((((-1.0)*x1819*x1820))+new_r01); |
| evalcond[6]=((((-1.0)*new_r01*x1820))+x1819+((cj0*new_r11))); |
| evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x1818); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); |
| if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| { |
| bgotonextstatement=false; |
| { |
| IkReal j2eval[1]; |
| new_r21=0; |
| new_r20=0; |
| new_r02=0; |
| new_r12=0; |
| j2eval[0]=IKabs(new_r22); |
| if( IKabs(j2eval[0]) < 0.0000000100000000 ) |
| { |
| continue; // no branches [j2] |
| |
| } else |
| { |
| IkReal op[2+1], zeror[2]; |
| int numroots; |
| op[0]=((-1.0)*new_r22); |
| op[1]=0; |
| op[2]=new_r22; |
| polyroots2(op,zeror,numroots); |
| IkReal j2array[2], cj2array[2], sj2array[2], tempj2array[1]; |
| int numsolutions = 0; |
| for(int ij2 = 0; ij2 < numroots; ++ij2) |
| { |
| IkReal htj2 = zeror[ij2]; |
| tempj2array[0]=((2.0)*(atan(htj2))); |
| for(int kj2 = 0; kj2 < 1; ++kj2) |
| { |
| j2array[numsolutions] = tempj2array[kj2]; |
| if( j2array[numsolutions] > IKPI ) |
| { |
| j2array[numsolutions]-=IK2PI; |
| } |
| else if( j2array[numsolutions] < -IKPI ) |
| { |
| j2array[numsolutions]+=IK2PI; |
| } |
| sj2array[numsolutions] = IKsin(j2array[numsolutions]); |
| cj2array[numsolutions] = IKcos(j2array[numsolutions]); |
| numsolutions++; |
| } |
| } |
| bool j2valid[2]={true,true}; |
| _nj2 = 2; |
| for(int ij2 = 0; ij2 < numsolutions; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| htj2 = IKtan(j2/2); |
| |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < numsolutions; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| |
| } |
| |
| } |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| bool bgotonextstatement = true; |
| do |
| { |
| if( 1 ) |
| { |
| bgotonextstatement=false; |
| continue; // branch miss [j2] |
| |
| } |
| } while(0); |
| if( bgotonextstatement ) |
| { |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x1822=IKPowWithIntegerCheck(cj1,-1); |
| if(!x1822.valid){ |
| continue; |
| } |
| IkReal x1821=x1822.value; |
| CheckValue<IkReal> x1823=IKPowWithIntegerCheck(sj0,-1); |
| if(!x1823.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1824=IKPowWithIntegerCheck(sj1,-1); |
| if(!x1824.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j2array[0]=IKatan2((new_r20*x1821), (x1821*(x1823.value)*(x1824.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11)))))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[12]; |
| IkReal x1825=IKsin(j2); |
| IkReal x1826=IKcos(j2); |
| IkReal x1827=((1.0)*sj0); |
| IkReal x1828=(cj0*new_r00); |
| IkReal x1829=((1.0)*cj0); |
| IkReal x1830=((1.0)*x1826); |
| IkReal x1831=(sj1*x1825); |
| IkReal x1832=(sj1*x1826); |
| IkReal x1833=((1.0)*x1825); |
| evalcond[0]=(new_r20+(((-1.0)*cj1*x1833))); |
| evalcond[1]=(new_r21+(((-1.0)*cj1*x1830))); |
| evalcond[2]=((((-1.0)*new_r01*x1827))+x1825+((cj0*new_r11))); |
| evalcond[3]=((((-1.0)*new_r10*x1829))+((new_r00*sj0))+x1826); |
| evalcond[4]=(((new_r10*sj0))+x1828+x1831); |
| evalcond[5]=(((new_r11*sj0))+x1832+((cj0*new_r01))); |
| evalcond[6]=(((cj0*x1831))+((sj0*x1826))+new_r00); |
| evalcond[7]=(((cj0*x1825))+((sj0*x1832))+new_r11); |
| evalcond[8]=(((cj0*x1832))+(((-1.0)*x1825*x1827))+new_r01); |
| evalcond[9]=(((sj0*x1831))+(((-1.0)*x1826*x1829))+new_r10); |
| evalcond[10]=(((cj1*new_r20))+(((-1.0)*x1833))+(((-1.0)*sj1*x1828))+(((-1.0)*new_r10*sj1*x1827))); |
| evalcond[11]=(((cj1*new_r21))+(((-1.0)*new_r11*sj1*x1827))+(((-1.0)*x1830))+(((-1.0)*new_r01*sj1*x1829))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x1835=IKPowWithIntegerCheck(cj1,-1); |
| if(!x1835.valid){ |
| continue; |
| } |
| IkReal x1834=x1835.value; |
| CheckValue<IkReal> x1836=IKPowWithIntegerCheck(sj0,-1); |
| if(!x1836.valid){ |
| continue; |
| } |
| 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 ) |
| continue; |
| j2array[0]=IKatan2((new_r20*x1834), (x1834*(x1836.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00)))))); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[12]; |
| IkReal x1837=IKsin(j2); |
| IkReal x1838=IKcos(j2); |
| IkReal x1839=((1.0)*sj0); |
| IkReal x1840=(cj0*new_r00); |
| IkReal x1841=((1.0)*cj0); |
| IkReal x1842=((1.0)*x1838); |
| IkReal x1843=(sj1*x1837); |
| IkReal x1844=(sj1*x1838); |
| IkReal x1845=((1.0)*x1837); |
| evalcond[0]=((((-1.0)*cj1*x1845))+new_r20); |
| evalcond[1]=((((-1.0)*cj1*x1842))+new_r21); |
| evalcond[2]=((((-1.0)*new_r01*x1839))+x1837+((cj0*new_r11))); |
| evalcond[3]=((((-1.0)*new_r10*x1841))+((new_r00*sj0))+x1838); |
| evalcond[4]=(((new_r10*sj0))+x1843+x1840); |
| evalcond[5]=(((new_r11*sj0))+x1844+((cj0*new_r01))); |
| evalcond[6]=(((cj0*x1843))+((sj0*x1838))+new_r00); |
| evalcond[7]=(((cj0*x1837))+((sj0*x1844))+new_r11); |
| evalcond[8]=(((cj0*x1844))+(((-1.0)*x1837*x1839))+new_r01); |
| evalcond[9]=(((sj0*x1843))+new_r10+(((-1.0)*x1838*x1841))); |
| evalcond[10]=((((-1.0)*x1845))+((cj1*new_r20))+(((-1.0)*new_r10*sj1*x1839))+(((-1.0)*sj1*x1840))); |
| evalcond[11]=((((-1.0)*new_r11*sj1*x1839))+(((-1.0)*new_r01*sj1*x1841))+(((-1.0)*x1842))+((cj1*new_r21))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| |
| } else |
| { |
| { |
| IkReal j2array[1], cj2array[1], sj2array[1]; |
| bool j2valid[1]={false}; |
| _nj2 = 1; |
| CheckValue<IkReal> x1846=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| if(!x1846.valid){ |
| continue; |
| } |
| CheckValue<IkReal> x1847 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); |
| if(!x1847.valid){ |
| continue; |
| } |
| j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1846.value)))+(x1847.value)); |
| sj2array[0]=IKsin(j2array[0]); |
| cj2array[0]=IKcos(j2array[0]); |
| if( j2array[0] > IKPI ) |
| { |
| j2array[0]-=IK2PI; |
| } |
| else if( j2array[0] < -IKPI ) |
| { j2array[0]+=IK2PI; |
| } |
| j2valid[0] = true; |
| for(int ij2 = 0; ij2 < 1; ++ij2) |
| { |
| if( !j2valid[ij2] ) |
| { |
| continue; |
| } |
| _ij2[0] = ij2; _ij2[1] = -1; |
| for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| { |
| if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| { |
| j2valid[iij2]=false; _ij2[1] = iij2; break; |
| } |
| } |
| j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| { |
| IkReal evalcond[12]; |
| IkReal x1848=IKsin(j2); |
| IkReal x1849=IKcos(j2); |
| IkReal x1850=((1.0)*sj0); |
| IkReal x1851=(cj0*new_r00); |
| IkReal x1852=((1.0)*cj0); |
| IkReal x1853=((1.0)*x1849); |
| IkReal x1854=(sj1*x1848); |
| IkReal x1855=(sj1*x1849); |
| IkReal x1856=((1.0)*x1848); |
| evalcond[0]=(new_r20+(((-1.0)*cj1*x1856))); |
| evalcond[1]=(new_r21+(((-1.0)*cj1*x1853))); |
| evalcond[2]=(x1848+(((-1.0)*new_r01*x1850))+((cj0*new_r11))); |
| evalcond[3]=(((new_r00*sj0))+(((-1.0)*new_r10*x1852))+x1849); |
| evalcond[4]=(((new_r10*sj0))+x1851+x1854); |
| evalcond[5]=(((new_r11*sj0))+x1855+((cj0*new_r01))); |
| evalcond[6]=(((sj0*x1849))+new_r00+((cj0*x1854))); |
| evalcond[7]=(((cj0*x1848))+((sj0*x1855))+new_r11); |
| evalcond[8]=((((-1.0)*x1848*x1850))+new_r01+((cj0*x1855))); |
| evalcond[9]=((((-1.0)*x1849*x1852))+((sj0*x1854))+new_r10); |
| evalcond[10]=((((-1.0)*sj1*x1851))+((cj1*new_r20))+(((-1.0)*new_r10*sj1*x1850))+(((-1.0)*x1856))); |
| evalcond[11]=(((cj1*new_r21))+(((-1.0)*new_r11*sj1*x1850))+(((-1.0)*new_r01*sj1*x1852))+(((-1.0)*x1853))); |
| 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 ) |
| { |
| continue; |
| } |
| } |
| |
| { |
| std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| vinfos[0].jointtype = 1; |
| vinfos[0].foffset = j0; |
| vinfos[0].indices[0] = _ij0[0]; |
| vinfos[0].indices[1] = _ij0[1]; |
| vinfos[0].maxsolutions = _nj0; |
| vinfos[1].jointtype = 1; |
| vinfos[1].foffset = j1; |
| vinfos[1].indices[0] = _ij1[0]; |
| vinfos[1].indices[1] = _ij1[1]; |
| vinfos[1].maxsolutions = _nj1; |
| vinfos[2].jointtype = 1; |
| vinfos[2].foffset = j2; |
| vinfos[2].indices[0] = _ij2[0]; |
| vinfos[2].indices[1] = _ij2[1]; |
| vinfos[2].maxsolutions = _nj2; |
| vinfos[3].jointtype = 1; |
| vinfos[3].foffset = j3; |
| vinfos[3].indices[0] = _ij3[0]; |
| vinfos[3].indices[1] = _ij3[1]; |
| vinfos[3].maxsolutions = _nj3; |
| vinfos[4].jointtype = 1; |
| vinfos[4].foffset = j4; |
| vinfos[4].indices[0] = _ij4[0]; |
| vinfos[4].indices[1] = _ij4[1]; |
| vinfos[4].maxsolutions = _nj4; |
| vinfos[5].jointtype = 1; |
| vinfos[5].foffset = j5; |
| vinfos[5].indices[0] = _ij5[0]; |
| vinfos[5].indices[1] = _ij5[1]; |
| vinfos[5].maxsolutions = _nj5; |
| std::vector<int> vfree(0); |
| solutions.AddSolution(vinfos,vfree); |
| } |
| } |
| } |
| |
| } |
| |
| } |
| } |
| } |
| |
| } |
| |
| } |
| } |
| } |
| } |
| }static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots) |
| { |
| using std::complex; |
| if( rawcoeffs[0] == 0 ) { |
| // solve with one reduced degree |
| polyroots2(&rawcoeffs[1], &rawroots[0], numroots); |
| return; |
| } |
| IKFAST_ASSERT(rawcoeffs[0] != 0); |
| const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| complex<IkReal> coeffs[3]; |
| const int maxsteps = 110; |
| for(int i = 0; i < 3; ++i) { |
| coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| } |
| complex<IkReal> roots[3]; |
| IkReal err[3]; |
| roots[0] = complex<IkReal>(1,0); |
| roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| err[0] = 1.0; |
| err[1] = 1.0; |
| for(int i = 2; i < 3; ++i) { |
| roots[i] = roots[i-1]*roots[1]; |
| err[i] = 1.0; |
| } |
| for(int step = 0; step < maxsteps; ++step) { |
| bool changed = false; |
| for(int i = 0; i < 3; ++i) { |
| if ( err[i] >= tol ) { |
| changed = true; |
| // evaluate |
| complex<IkReal> x = roots[i] + coeffs[0]; |
| for(int j = 1; j < 3; ++j) { |
| x = roots[i] * x + coeffs[j]; |
| } |
| for(int j = 0; j < 3; ++j) { |
| if( i != j ) { |
| if( roots[i] != roots[j] ) { |
| x /= (roots[i] - roots[j]); |
| } |
| } |
| } |
| roots[i] -= x; |
| err[i] = abs(x); |
| } |
| } |
| if( !changed ) { |
| break; |
| } |
| } |
| |
| numroots = 0; |
| bool visited[3] = {false}; |
| for(int i = 0; i < 3; ++i) { |
| if( !visited[i] ) { |
| // might be a multiple root, in which case it will have more error than the other roots |
| // find any neighboring roots, and take the average |
| complex<IkReal> newroot=roots[i]; |
| int n = 1; |
| for(int j = i+1; j < 3; ++j) { |
| // care about error in real much more than imaginary |
| if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| newroot += roots[j]; |
| n += 1; |
| visited[j] = true; |
| } |
| } |
| if( n > 1 ) { |
| newroot /= n; |
| } |
| // 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 |
| if( IKabs(imag(newroot)) < tolsqrt ) { |
| rawroots[numroots++] = real(newroot); |
| } |
| } |
| } |
| } |
| static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) { |
| IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2]; |
| if( det < 0 ) { |
| numroots=0; |
| } |
| else if( det == 0 ) { |
| rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0]; |
| numroots = 1; |
| } |
| else { |
| det = IKsqrt(det); |
| rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]); |
| rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]); |
| numroots = 2; |
| } |
| } |
| static inline void polyroots5(IkReal rawcoeffs[5+1], IkReal rawroots[5], int& numroots) |
| { |
| using std::complex; |
| if( rawcoeffs[0] == 0 ) { |
| // solve with one reduced degree |
| polyroots4(&rawcoeffs[1], &rawroots[0], numroots); |
| return; |
| } |
| IKFAST_ASSERT(rawcoeffs[0] != 0); |
| const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| complex<IkReal> coeffs[5]; |
| const int maxsteps = 110; |
| for(int i = 0; i < 5; ++i) { |
| coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| } |
| complex<IkReal> roots[5]; |
| IkReal err[5]; |
| roots[0] = complex<IkReal>(1,0); |
| roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| err[0] = 1.0; |
| err[1] = 1.0; |
| for(int i = 2; i < 5; ++i) { |
| roots[i] = roots[i-1]*roots[1]; |
| err[i] = 1.0; |
| } |
| for(int step = 0; step < maxsteps; ++step) { |
| bool changed = false; |
| for(int i = 0; i < 5; ++i) { |
| if ( err[i] >= tol ) { |
| changed = true; |
| // evaluate |
| complex<IkReal> x = roots[i] + coeffs[0]; |
| for(int j = 1; j < 5; ++j) { |
| x = roots[i] * x + coeffs[j]; |
| } |
| for(int j = 0; j < 5; ++j) { |
| if( i != j ) { |
| if( roots[i] != roots[j] ) { |
| x /= (roots[i] - roots[j]); |
| } |
| } |
| } |
| roots[i] -= x; |
| err[i] = abs(x); |
| } |
| } |
| if( !changed ) { |
| break; |
| } |
| } |
| |
| numroots = 0; |
| bool visited[5] = {false}; |
| for(int i = 0; i < 5; ++i) { |
| if( !visited[i] ) { |
| // might be a multiple root, in which case it will have more error than the other roots |
| // find any neighboring roots, and take the average |
| complex<IkReal> newroot=roots[i]; |
| int n = 1; |
| for(int j = i+1; j < 5; ++j) { |
| // care about error in real much more than imaginary |
| if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| newroot += roots[j]; |
| n += 1; |
| visited[j] = true; |
| } |
| } |
| if( n > 1 ) { |
| newroot /= n; |
| } |
| // 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 |
| if( IKabs(imag(newroot)) < tolsqrt ) { |
| rawroots[numroots++] = real(newroot); |
| } |
| } |
| } |
| } |
| static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots) |
| { |
| using std::complex; |
| if( rawcoeffs[0] == 0 ) { |
| // solve with one reduced degree |
| polyroots3(&rawcoeffs[1], &rawroots[0], numroots); |
| return; |
| } |
| IKFAST_ASSERT(rawcoeffs[0] != 0); |
| const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| complex<IkReal> coeffs[4]; |
| const int maxsteps = 110; |
| for(int i = 0; i < 4; ++i) { |
| coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| } |
| complex<IkReal> roots[4]; |
| IkReal err[4]; |
| roots[0] = complex<IkReal>(1,0); |
| roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| err[0] = 1.0; |
| err[1] = 1.0; |
| for(int i = 2; i < 4; ++i) { |
| roots[i] = roots[i-1]*roots[1]; |
| err[i] = 1.0; |
| } |
| for(int step = 0; step < maxsteps; ++step) { |
| bool changed = false; |
| for(int i = 0; i < 4; ++i) { |
| if ( err[i] >= tol ) { |
| changed = true; |
| // evaluate |
| complex<IkReal> x = roots[i] + coeffs[0]; |
| for(int j = 1; j < 4; ++j) { |
| x = roots[i] * x + coeffs[j]; |
| } |
| for(int j = 0; j < 4; ++j) { |
| if( i != j ) { |
| if( roots[i] != roots[j] ) { |
| x /= (roots[i] - roots[j]); |
| } |
| } |
| } |
| roots[i] -= x; |
| err[i] = abs(x); |
| } |
| } |
| if( !changed ) { |
| break; |
| } |
| } |
| |
| numroots = 0; |
| bool visited[4] = {false}; |
| for(int i = 0; i < 4; ++i) { |
| if( !visited[i] ) { |
| // might be a multiple root, in which case it will have more error than the other roots |
| // find any neighboring roots, and take the average |
| complex<IkReal> newroot=roots[i]; |
| int n = 1; |
| for(int j = i+1; j < 4; ++j) { |
| // care about error in real much more than imaginary |
| if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| newroot += roots[j]; |
| n += 1; |
| visited[j] = true; |
| } |
| } |
| if( n > 1 ) { |
| newroot /= n; |
| } |
| // 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 |
| if( IKabs(imag(newroot)) < tolsqrt ) { |
| rawroots[numroots++] = real(newroot); |
| } |
| } |
| } |
| } |
| static inline void polyroots7(IkReal rawcoeffs[7+1], IkReal rawroots[7], int& numroots) |
| { |
| using std::complex; |
| if( rawcoeffs[0] == 0 ) { |
| // solve with one reduced degree |
| polyroots6(&rawcoeffs[1], &rawroots[0], numroots); |
| return; |
| } |
| IKFAST_ASSERT(rawcoeffs[0] != 0); |
| const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| complex<IkReal> coeffs[7]; |
| const int maxsteps = 110; |
| for(int i = 0; i < 7; ++i) { |
| coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| } |
| complex<IkReal> roots[7]; |
| IkReal err[7]; |
| roots[0] = complex<IkReal>(1,0); |
| roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| err[0] = 1.0; |
| err[1] = 1.0; |
| for(int i = 2; i < 7; ++i) { |
| roots[i] = roots[i-1]*roots[1]; |
| err[i] = 1.0; |
| } |
| for(int step = 0; step < maxsteps; ++step) { |
| bool changed = false; |
| for(int i = 0; i < 7; ++i) { |
| if ( err[i] >= tol ) { |
| changed = true; |
| // evaluate |
| complex<IkReal> x = roots[i] + coeffs[0]; |
| for(int j = 1; j < 7; ++j) { |
| x = roots[i] * x + coeffs[j]; |
| } |
| for(int j = 0; j < 7; ++j) { |
| if( i != j ) { |
| if( roots[i] != roots[j] ) { |
| x /= (roots[i] - roots[j]); |
| } |
| } |
| } |
| roots[i] -= x; |
| err[i] = abs(x); |
| } |
| } |
| if( !changed ) { |
| break; |
| } |
| } |
| |
| numroots = 0; |
| bool visited[7] = {false}; |
| for(int i = 0; i < 7; ++i) { |
| if( !visited[i] ) { |
| // might be a multiple root, in which case it will have more error than the other roots |
| // find any neighboring roots, and take the average |
| complex<IkReal> newroot=roots[i]; |
| int n = 1; |
| for(int j = i+1; j < 7; ++j) { |
| // care about error in real much more than imaginary |
| if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| newroot += roots[j]; |
| n += 1; |
| visited[j] = true; |
| } |
| } |
| if( n > 1 ) { |
| newroot /= n; |
| } |
| // 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 |
| if( IKabs(imag(newroot)) < tolsqrt ) { |
| rawroots[numroots++] = real(newroot); |
| } |
| } |
| } |
| } |
| static inline void polyroots6(IkReal rawcoeffs[6+1], IkReal rawroots[6], int& numroots) |
| { |
| using std::complex; |
| if( rawcoeffs[0] == 0 ) { |
| // solve with one reduced degree |
| polyroots5(&rawcoeffs[1], &rawroots[0], numroots); |
| return; |
| } |
| IKFAST_ASSERT(rawcoeffs[0] != 0); |
| const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| complex<IkReal> coeffs[6]; |
| const int maxsteps = 110; |
| for(int i = 0; i < 6; ++i) { |
| coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| } |
| complex<IkReal> roots[6]; |
| IkReal err[6]; |
| roots[0] = complex<IkReal>(1,0); |
| roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| err[0] = 1.0; |
| err[1] = 1.0; |
| for(int i = 2; i < 6; ++i) { |
| roots[i] = roots[i-1]*roots[1]; |
| err[i] = 1.0; |
| } |
| for(int step = 0; step < maxsteps; ++step) { |
| bool changed = false; |
| for(int i = 0; i < 6; ++i) { |
| if ( err[i] >= tol ) { |
| changed = true; |
| // evaluate |
| complex<IkReal> x = roots[i] + coeffs[0]; |
| for(int j = 1; j < 6; ++j) { |
| x = roots[i] * x + coeffs[j]; |
| } |
| for(int j = 0; j < 6; ++j) { |
| if( i != j ) { |
| if( roots[i] != roots[j] ) { |
| x /= (roots[i] - roots[j]); |
| } |
| } |
| } |
| roots[i] -= x; |
| err[i] = abs(x); |
| } |
| } |
| if( !changed ) { |
| break; |
| } |
| } |
| |
| numroots = 0; |
| bool visited[6] = {false}; |
| for(int i = 0; i < 6; ++i) { |
| if( !visited[i] ) { |
| // might be a multiple root, in which case it will have more error than the other roots |
| // find any neighboring roots, and take the average |
| complex<IkReal> newroot=roots[i]; |
| int n = 1; |
| for(int j = i+1; j < 6; ++j) { |
| // care about error in real much more than imaginary |
| if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| newroot += roots[j]; |
| n += 1; |
| visited[j] = true; |
| } |
| } |
| if( n > 1 ) { |
| newroot /= n; |
| } |
| // 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 |
| if( IKabs(imag(newroot)) < tolsqrt ) { |
| rawroots[numroots++] = real(newroot); |
| } |
| } |
| } |
| } |
| static inline void polyroots8(IkReal rawcoeffs[8+1], IkReal rawroots[8], int& numroots) |
| { |
| using std::complex; |
| if( rawcoeffs[0] == 0 ) { |
| // solve with one reduced degree |
| polyroots7(&rawcoeffs[1], &rawroots[0], numroots); |
| return; |
| } |
| IKFAST_ASSERT(rawcoeffs[0] != 0); |
| const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| complex<IkReal> coeffs[8]; |
| const int maxsteps = 110; |
| for(int i = 0; i < 8; ++i) { |
| coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| } |
| complex<IkReal> roots[8]; |
| IkReal err[8]; |
| roots[0] = complex<IkReal>(1,0); |
| roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| err[0] = 1.0; |
| err[1] = 1.0; |
| for(int i = 2; i < 8; ++i) { |
| roots[i] = roots[i-1]*roots[1]; |
| err[i] = 1.0; |
| } |
| for(int step = 0; step < maxsteps; ++step) { |
| bool changed = false; |
| for(int i = 0; i < 8; ++i) { |
| if ( err[i] >= tol ) { |
| changed = true; |
| // evaluate |
| complex<IkReal> x = roots[i] + coeffs[0]; |
| for(int j = 1; j < 8; ++j) { |
| x = roots[i] * x + coeffs[j]; |
| } |
| for(int j = 0; j < 8; ++j) { |
| if( i != j ) { |
| if( roots[i] != roots[j] ) { |
| x /= (roots[i] - roots[j]); |
| } |
| } |
| } |
| roots[i] -= x; |
| err[i] = abs(x); |
| } |
| } |
| if( !changed ) { |
| break; |
| } |
| } |
| |
| numroots = 0; |
| bool visited[8] = {false}; |
| for(int i = 0; i < 8; ++i) { |
| if( !visited[i] ) { |
| // might be a multiple root, in which case it will have more error than the other roots |
| // find any neighboring roots, and take the average |
| complex<IkReal> newroot=roots[i]; |
| int n = 1; |
| for(int j = i+1; j < 8; ++j) { |
| // care about error in real much more than imaginary |
| if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| newroot += roots[j]; |
| n += 1; |
| visited[j] = true; |
| } |
| } |
| if( n > 1 ) { |
| newroot /= n; |
| } |
| // 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 |
| if( IKabs(imag(newroot)) < tolsqrt ) { |
| rawroots[numroots++] = real(newroot); |
| } |
| } |
| } |
| } |
| }; |
| |
| |
| /// solves the inverse kinematics equations. |
| /// \param pfree is an array specifying the free joints of the chain. |
| IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) { |
| IKSolver solver; |
| return solver.ComputeIk(eetrans,eerot,pfree,solutions); |
| } |
| |
| IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions, void* pOpenRAVEManip) { |
| IKSolver solver; |
| return solver.ComputeIk(eetrans,eerot,pfree,solutions); |
| } |
| |
| IKFAST_API const char* GetKinematicsHash() { return "<robot:GenericRobot - hya (58dbf1259c2cdf57f1e3d77f555c8c6b)>"; } |
| |
| IKFAST_API const char* GetIkFastVersion() { return "0x1000004a"; } |
| |
| #ifdef IKFAST_NAMESPACE |
| } // end namespace |
| #endif |
| |
| #ifndef IKFAST_NO_MAIN |
| #include <stdio.h> |
| #include <stdlib.h> |
| #ifdef IKFAST_NAMESPACE |
| using namespace IKFAST_NAMESPACE; |
| #endif |
| int main(int argc, char** argv) |
| { |
| if( argc != 12+GetNumFreeParameters()+1 ) { |
| printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n" |
| "Returns the ik solutions given the transformation of the end effector specified by\n" |
| "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n" |
| "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters()); |
| return 1; |
| } |
| |
| IkSolutionList<IkReal> solutions; |
| std::vector<IkReal> vfree(GetNumFreeParameters()); |
| IkReal eerot[9],eetrans[3]; |
| eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]); |
| eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]); |
| eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]); |
| for(std::size_t i = 0; i < vfree.size(); ++i) |
| vfree[i] = atof(argv[13+i]); |
| bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions); |
| |
| if( !bSuccess ) { |
| fprintf(stderr,"Failed to get ik solution\n"); |
| return -1; |
| } |
| |
| printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions()); |
| std::vector<IkReal> solvalues(GetNumJoints()); |
| for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) { |
| const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i); |
| printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size()); |
| std::vector<IkReal> vsolfree(sol.GetFree().size()); |
| sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL); |
| for( std::size_t j = 0; j < solvalues.size(); ++j) |
| printf("%.15f, ", solvalues[j]); |
| printf("\n"); |
| } |
| return 0; |
| } |
| |
| #endif |