Classes | Macros | Functions
fanuc_lrmate200id7l_manipulator_ikfast_solver.cpp File Reference
#include "ikfast.h"
#include <cmath>
#include <vector>
#include <limits>
#include <algorithm>
#include <complex>
#include <stdexcept>
#include <sstream>
#include <iostream>
#include <stdio.h>
#include <stdlib.h>
Include dependency graph for fanuc_lrmate200id7l_manipulator_ikfast_solver.cpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  CheckValue< T >
 
class  IKSolver
 

Macros

#define __PRETTY_FUNCTION__   __func__
 
#define __PRETTY_FUNCTION__   __func__
 
#define IK2PI   ((IkReal)6.28318530717959)
 
#define IK2PI   ((IkReal)6.28318530717959)
 
#define IKFAST_ALIGNED16(x)   x __attribute((aligned(16)))
 
#define IKFAST_ALIGNED16(x)   x __attribute((aligned(16)))
 
#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()); } }
 
#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()); } }
 
#define IKFAST_ATAN2_MAGTHRESH   ((IkReal)1e-7)
 
#define IKFAST_ATAN2_MAGTHRESH   ((IkReal)1e-7)
 
#define IKFAST_COMPILE_ASSERT(x)   extern int __dummy[(int)x]
 
#define IKFAST_COMPILE_ASSERT(x)   extern int __dummy[(int)x]
 
#define IKFAST_EVALCOND_THRESH   ((IkReal)0.00001)
 
#define IKFAST_EVALCOND_THRESH   ((IkReal)0.00001)
 
#define IKFAST_HAS_LIBRARY
 
#define IKFAST_HAS_LIBRARY
 
#define IKFAST_SINCOS_THRESH   ((IkReal)1e-7)
 
#define IKFAST_SINCOS_THRESH   ((IkReal)1e-7)
 
#define IKFAST_SOLUTION_THRESH   ((IkReal)1e-6)
 
#define IKFAST_SOLUTION_THRESH   ((IkReal)1e-6)
 
#define IKPI   ((IkReal)3.14159265358979)
 
#define IKPI   ((IkReal)3.14159265358979)
 
#define IKPI_2   ((IkReal)1.57079632679490)
 
#define IKPI_2   ((IkReal)1.57079632679490)
 

Functions

IKFAST_API void ComputeFk (const IkReal *j, IkReal *eetrans, IkReal *eerot)
 
IKFAST_API bool ComputeIk (const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
 
IKFAST_API bool ComputeIk2 (const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions, void *pOpenRAVEManip)
 
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)
 
void dgesv_ (const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info)
 
void dgetrf_ (const int *m, const int *n, 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 dgetrs_ (const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info)
 
IKFAST_API int * GetFreeParameters ()
 
IKFAST_API const char * GetIkFastVersion ()
 
IKFAST_API int GetIkRealSize ()
 
IKFAST_API int GetIkType ()
 
IKFAST_API const char * GetKinematicsHash ()
 
IKFAST_API int GetNumFreeParameters ()
 
IKFAST_API int GetNumJoints ()
 
float IKabs (float f)
 
double IKabs (double f)
 
float IKacos (float f)
 
double IKacos (double f)
 
float IKasin (float f)
 
double IKasin (double f)
 
float IKatan2 (float fy, float fx)
 
double IKatan2 (double fy, double fx)
 
float IKatan2Simple (float fy, float fx)
 
double IKatan2Simple (double fy, double fx)
 
template<typename T >
CheckValue< T > IKatan2WithCheck (T fy, T fx, T epsilon)
 
float IKcos (float f)
 
double IKcos (double f)
 
 IKFAST_COMPILE_ASSERT (IKFAST_VERSION==0x10000049)
 
float IKfmod (float x, float y)
 
double IKfmod (double x, double y)
 
float IKlog (float f)
 
double IKlog (double f)
 
template<typename T >
CheckValue< T > IKPowWithIntegerCheck (T f, int n)
 
float IKsign (float f)
 
double IKsign (double f)
 
float IKsin (float f)
 
double IKsin (double f)
 
float IKsqr (float f)
 
double IKsqr (double f)
 
float IKsqrt (float f)
 
double IKsqrt (double f)
 
float IKtan (float f)
 
double IKtan (double f)
 
int main (int argc, char **argv)
 
void zgetrf_ (const int *m, const int *n, std::complex< double > *a, const int *lda, int *ipiv, int *info)
 

Macro Definition Documentation

#define __PRETTY_FUNCTION__   __func__
#define __PRETTY_FUNCTION__   __func__
#define IK2PI   ((IkReal)6.28318530717959)
#define IK2PI   ((IkReal)6.28318530717959)
#define IKFAST_ALIGNED16 (   x)    x __attribute((aligned(16)))
#define IKFAST_ALIGNED16 (   x)    x __attribute((aligned(16)))
#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()); } }
#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()); } }
#define IKFAST_ATAN2_MAGTHRESH   ((IkReal)1e-7)
#define IKFAST_ATAN2_MAGTHRESH   ((IkReal)1e-7)
#define IKFAST_COMPILE_ASSERT (   x)    extern int __dummy[(int)x]
#define IKFAST_COMPILE_ASSERT (   x)    extern int __dummy[(int)x]
#define IKFAST_EVALCOND_THRESH   ((IkReal)0.00001)
#define IKFAST_EVALCOND_THRESH   ((IkReal)0.00001)
#define IKFAST_HAS_LIBRARY
#define IKFAST_HAS_LIBRARY

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 0x10000049 generated on 2019-09-19 18:45:56.462233 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

Definition at line 20 of file fanuc_lrmate200id7l_manipulator_ikfast_solver.cpp.

#define IKFAST_SINCOS_THRESH   ((IkReal)1e-7)
#define IKFAST_SINCOS_THRESH   ((IkReal)1e-7)
#define IKFAST_SOLUTION_THRESH   ((IkReal)1e-6)
#define IKFAST_SOLUTION_THRESH   ((IkReal)1e-6)
#define IKPI   ((IkReal)3.14159265358979)
#define IKPI   ((IkReal)3.14159265358979)
#define IKPI_2   ((IkReal)1.57079632679490)
#define IKPI_2   ((IkReal)1.57079632679490)

Function Documentation

IKFAST_API void ComputeFk ( const IkReal *  j,
IkReal *  eetrans,
IkReal *  eerot 
)

solves the forward kinematics equations.

Parameters
pfreeis an array specifying the free joints of the chain.

Definition at line 299 of file fanuc_lrmate200id7l_manipulator_ikfast_solver.cpp.

IKFAST_API bool ComputeIk ( const IkReal *  eetrans,
const IkReal *  eerot,
const IkReal *  pfree,
IkSolutionListBase< IkReal > &  solutions 
)

solves the inverse kinematics equations.

Parameters
pfreeis an array specifying the free joints of the chain.

Definition at line 19963 of file fanuc_lrmate200id7l_manipulator_ikfast_solver.cpp.

IKFAST_API bool ComputeIk2 ( const IkReal *  eetrans,
const IkReal *  eerot,
const IkReal *  pfree,
IkSolutionListBase< IkReal > &  solutions,
void *  pOpenRAVEManip 
)
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 
)
void dgesv_ ( const int *  n,
const int *  nrhs,
double *  a,
const int *  lda,
int *  ipiv,
double *  b,
const int *  ldb,
int *  info 
)
void dgetrf_ ( const int *  m,
const int *  n,
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 dgetrs_ ( const char *  trans,
const int *  n,
const int *  nrhs,
double *  a,
const int *  lda,
int *  ipiv,
double *  b,
const int *  ldb,
int *  info 
)
IKFAST_API int* GetFreeParameters ( )
IKFAST_API const char* GetIkFastVersion ( )
IKFAST_API int GetIkRealSize ( )
IKFAST_API int GetIkType ( )
IKFAST_API const char* GetKinematicsHash ( )
IKFAST_API int GetNumFreeParameters ( )
IKFAST_API int GetNumJoints ( )
float IKabs ( float  f)
inline
double IKabs ( double  f)
inline
float IKacos ( float  f)
inline
double IKacos ( double  f)
inline
float IKasin ( float  f)
inline
double IKasin ( double  f)
inline
float IKatan2 ( float  fy,
float  fx 
)
inline
double IKatan2 ( double  fy,
double  fx 
)
inline
float IKatan2Simple ( float  fy,
float  fx 
)
inline
double IKatan2Simple ( double  fy,
double  fx 
)
inline
template<typename T >
CheckValue<T> IKatan2WithCheck ( fy,
fx,
epsilon 
)
inline
float IKcos ( float  f)
inline
double IKcos ( double  f)
inline
IKFAST_COMPILE_ASSERT ( IKFAST_VERSION  = =0x10000049)
float IKfmod ( float  x,
float  y 
)
inline
double IKfmod ( double  x,
double  y 
)
inline
float IKlog ( float  f)
inline
double IKlog ( double  f)
inline
template<typename T >
CheckValue<T> IKPowWithIntegerCheck ( f,
int  n 
)
inline
float IKsign ( float  f)
inline
double IKsign ( double  f)
inline
float IKsin ( float  f)
inline
double IKsin ( double  f)
inline
float IKsqr ( float  f)
inline
double IKsqr ( double  f)
inline
float IKsqrt ( float  f)
inline
double IKsqrt ( double  f)
inline
float IKtan ( float  f)
inline
double IKtan ( double  f)
inline
int main ( int  argc,
char **  argv 
)
void zgetrf_ ( const int *  m,
const int *  n,
std::complex< double > *  a,
const int *  lda,
int *  ipiv,
int *  info 
)


fanuc_lrmate200id_moveit_plugins
Author(s): G.A. vd. Hoorn (TU Delft Robotics Institute)
autogenerated on Tue Mar 23 2021 02:10:01