Classes | Enumerations | Functions
ikfast_kinematics_plugin Namespace Reference

Classes

struct  CheckValue
class  IKFastKinematicsPlugin
class  IKSolver

Enumerations

enum  IkParameterizationType {
  IKP_None = 0, IKP_Transform6D = 0x67000001, IKP_Rotation3D = 0x34000002, IKP_Translation3D = 0x33000003,
  IKP_Direction3D = 0x23000004, IKP_Ray4D = 0x46000005, IKP_Lookat3D = 0x23000006, IKP_TranslationDirection5D = 0x56000007,
  IKP_TranslationXY2D = 0x22000008, IKP_TranslationXYOrientation3D = 0x33000009, IKP_TranslationLocalGlobal6D = 0x3600000a, IKP_TranslationXAxisAngle4D = 0x4400000b,
  IKP_TranslationYAxisAngle4D = 0x4400000c, IKP_TranslationZAxisAngle4D = 0x4400000d, IKP_TranslationXAxisAngleZNorm4D = 0x4400000e, IKP_TranslationYAxisAngleXNorm4D = 0x4400000f,
  IKP_TranslationZAxisAngleYNorm4D = 0x44000010, IKP_NumberOfParameterizations = 16, IKP_VelocityDataBit = 0x00008000, IKP_Transform6DVelocity = IKP_Transform6D|IKP_VelocityDataBit,
  IKP_Rotation3DVelocity = IKP_Rotation3D|IKP_VelocityDataBit, IKP_Translation3DVelocity = IKP_Translation3D|IKP_VelocityDataBit, IKP_Direction3DVelocity = IKP_Direction3D|IKP_VelocityDataBit, IKP_Ray4DVelocity = IKP_Ray4D|IKP_VelocityDataBit,
  IKP_Lookat3DVelocity = IKP_Lookat3D|IKP_VelocityDataBit, IKP_TranslationDirection5DVelocity = IKP_TranslationDirection5D|IKP_VelocityDataBit, IKP_TranslationXY2DVelocity = IKP_TranslationXY2D|IKP_VelocityDataBit, IKP_TranslationXYOrientation3DVelocity = IKP_TranslationXYOrientation3D|IKP_VelocityDataBit,
  IKP_TranslationLocalGlobal6DVelocity = IKP_TranslationLocalGlobal6D|IKP_VelocityDataBit, IKP_TranslationXAxisAngle4DVelocity = IKP_TranslationXAxisAngle4D|IKP_VelocityDataBit, IKP_TranslationYAxisAngle4DVelocity = IKP_TranslationYAxisAngle4D|IKP_VelocityDataBit, IKP_TranslationZAxisAngle4DVelocity = IKP_TranslationZAxisAngle4D|IKP_VelocityDataBit,
  IKP_TranslationXAxisAngleZNorm4DVelocity = IKP_TranslationXAxisAngleZNorm4D|IKP_VelocityDataBit, IKP_TranslationYAxisAngleXNorm4DVelocity = IKP_TranslationYAxisAngleXNorm4D|IKP_VelocityDataBit, IKP_TranslationZAxisAngleYNorm4DVelocity = IKP_TranslationZAxisAngleYNorm4D|IKP_VelocityDataBit, IKP_UniqueIdMask = 0x0000ffff,
  IKP_CustomDataBit = 0x00010000
}
 The types of inverse kinematics parameterizations supported. More...

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< TIKatan2WithCheck (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< TIKPowWithIntegerCheck (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)
void zgetrf_ (const int *m, const int *n, std::complex< double > *a, const int *lda, int *ipiv, int *info)

Enumeration Type Documentation

The types of inverse kinematics parameterizations supported.

The minimum degree of freedoms required is set in the upper 4 bits of each type. The number of values used to represent the parameterization ( >= dof ) is the next 4 bits. The lower bits contain a unique id of the type.

Enumerator:
IKP_None 
IKP_Transform6D 

end effector reaches desired 6D transformation

IKP_Rotation3D 

end effector reaches desired 3D rotation

IKP_Translation3D 

end effector origin reaches desired 3D translation

IKP_Direction3D 

direction on end effector coordinate system reaches desired direction

IKP_Ray4D 

ray on end effector coordinate system reaches desired global ray

IKP_Lookat3D 

direction on end effector coordinate system points to desired 3D position

IKP_TranslationDirection5D 

end effector origin and direction reaches desired 3D translation and direction. Can be thought of as Ray IK where the origin of the ray must coincide.

IKP_TranslationXY2D 

2D translation along XY plane

IKP_TranslationXYOrientation3D 

2D translation along XY plane and 1D rotation around Z axis. The offset of the rotation is measured starting at +X, so at +X is it 0, at +Y it is pi/2.

IKP_TranslationLocalGlobal6D 

local point on end effector origin reaches desired 3D global point

IKP_TranslationXAxisAngle4D 

end effector origin reaches desired 3D translation, manipulator direction makes a specific angle with x-axis like a cone, angle is from 0-pi. Axes defined in the manipulator base link's coordinate system)

IKP_TranslationYAxisAngle4D 

end effector origin reaches desired 3D translation, manipulator direction makes a specific angle with y-axis like a cone, angle is from 0-pi. Axes defined in the manipulator base link's coordinate system)

IKP_TranslationZAxisAngle4D 

end effector origin reaches desired 3D translation, manipulator direction makes a specific angle with z-axis like a cone, angle is from 0-pi. Axes are defined in the manipulator base link's coordinate system.

IKP_TranslationXAxisAngleZNorm4D 

end effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z-axis and be rotated at a certain angle starting from the x-axis (defined in the manipulator base link's coordinate system)

IKP_TranslationYAxisAngleXNorm4D 

end effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to x-axis and be rotated at a certain angle starting from the y-axis (defined in the manipulator base link's coordinate system)

IKP_TranslationZAxisAngleYNorm4D 

end effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to y-axis and be rotated at a certain angle starting from the z-axis (defined in the manipulator base link's coordinate system)

IKP_NumberOfParameterizations 

number of parameterizations (does not count IKP_None)

IKP_VelocityDataBit 

bit is set if the data represents the time-derivate velocity of an IkParameterization

IKP_Transform6DVelocity 
IKP_Rotation3DVelocity 
IKP_Translation3DVelocity 
IKP_Direction3DVelocity 
IKP_Ray4DVelocity 
IKP_Lookat3DVelocity 
IKP_TranslationDirection5DVelocity 
IKP_TranslationXY2DVelocity 
IKP_TranslationXYOrientation3DVelocity 
IKP_TranslationLocalGlobal6DVelocity 
IKP_TranslationXAxisAngle4DVelocity 
IKP_TranslationYAxisAngle4DVelocity 
IKP_TranslationZAxisAngle4DVelocity 
IKP_TranslationXAxisAngleZNorm4DVelocity 
IKP_TranslationYAxisAngleXNorm4DVelocity 
IKP_TranslationZAxisAngleYNorm4DVelocity 
IKP_UniqueIdMask 

the mask for the unique ids

IKP_CustomDataBit 

bit is set if the ikparameterization contains custom data, this is only used when serializing the ik parameterizations

Definition at line 83 of file fetch_arm_ikfast_moveit_plugin.cpp.


Function Documentation

IKFAST_API void ikfast_kinematics_plugin::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 300 of file fetch_arm_ikfast_moveit_plugin.cpp.

IKFAST_API bool ikfast_kinematics_plugin::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 17438 of file fetch_arm_ikfast_moveit_plugin.cpp.

IKFAST_API bool ikfast_kinematics_plugin::ComputeIk2 ( const IkReal *  eetrans,
const IkReal *  eerot,
const IkReal *  pfree,
IkSolutionListBase< IkReal > &  solutions,
void *  pOpenRAVEManip 
)

Definition at line 17443 of file fetch_arm_ikfast_moveit_plugin.cpp.

void ikfast_kinematics_plugin::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 ikfast_kinematics_plugin::dgesv_ ( const int *  n,
const int *  nrhs,
double *  a,
const int *  lda,
int *  ipiv,
double *  b,
const int *  ldb,
int *  info 
)
void ikfast_kinematics_plugin::dgetrf_ ( const int *  m,
const int *  n,
double *  a,
const int *  lda,
int *  ipiv,
int *  info 
)
void ikfast_kinematics_plugin::dgetri_ ( const int *  n,
const double *  a,
const int *  lda,
int *  ipiv,
double *  work,
const int *  lwork,
int *  info 
)
void ikfast_kinematics_plugin::dgetrs_ ( const char *  trans,
const int *  n,
const int *  nrhs,
double *  a,
const int *  lda,
int *  ipiv,
double *  b,
const int *  ldb,
int *  info 
)

Definition at line 377 of file fetch_arm_ikfast_moveit_plugin.cpp.

IKFAST_API const char* ikfast_kinematics_plugin::GetIkFastVersion ( )

Definition at line 17450 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 380 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 382 of file fetch_arm_ikfast_moveit_plugin.cpp.

IKFAST_API const char* ikfast_kinematics_plugin::GetKinematicsHash ( )

Definition at line 17448 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 376 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 378 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKabs ( float  f) [inline]

Definition at line 92 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKabs ( double  f) [inline]

Definition at line 93 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKacos ( float  f) [inline]

Definition at line 155 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKacos ( double  f) [inline]

Definition at line 162 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKasin ( float  f) [inline]

Definition at line 122 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKasin ( double  f) [inline]

Definition at line 129 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKatan2 ( float  fy,
float  fx 
) [inline]

Definition at line 180 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKatan2 ( double  fy,
double  fx 
) [inline]

Definition at line 193 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKatan2Simple ( float  fy,
float  fx 
) [inline]

Definition at line 177 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKatan2Simple ( double  fy,
double  fx 
) [inline]

Definition at line 190 of file fetch_arm_ikfast_moveit_plugin.cpp.

template<typename T >
CheckValue<T> ikfast_kinematics_plugin::IKatan2WithCheck ( T  fy,
T  fx,
T  epsilon 
) [inline]

Definition at line 212 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKcos ( float  f) [inline]

Definition at line 171 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKcos ( double  f) [inline]

Definition at line 172 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKfmod ( float  x,
float  y 
) [inline]

Definition at line 138 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKfmod ( double  x,
double  y 
) [inline]

Definition at line 147 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKlog ( float  f) [inline]

Definition at line 98 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKlog ( double  f) [inline]

Definition at line 99 of file fetch_arm_ikfast_moveit_plugin.cpp.

template<typename T >
CheckValue<T> ikfast_kinematics_plugin::IKPowWithIntegerCheck ( T  f,
int  n 
) [inline]

Definition at line 247 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKsign ( float  f) [inline]

Definition at line 226 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKsign ( double  f) [inline]

Definition at line 236 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKsin ( float  f) [inline]

Definition at line 169 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKsin ( double  f) [inline]

Definition at line 170 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKsqr ( float  f) [inline]

Definition at line 95 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKsqr ( double  f) [inline]

Definition at line 96 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKsqrt ( float  f) [inline]

Definition at line 175 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKsqrt ( double  f) [inline]

Definition at line 176 of file fetch_arm_ikfast_moveit_plugin.cpp.

float ikfast_kinematics_plugin::IKtan ( float  f) [inline]

Definition at line 173 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKtan ( double  f) [inline]

Definition at line 174 of file fetch_arm_ikfast_moveit_plugin.cpp.

void ikfast_kinematics_plugin::zgetrf_ ( const int *  m,
const int *  n,
std::complex< double > *  a,
const int *  lda,
int *  ipiv,
int *  info 
)


fetch_ikfast_plugin
Author(s): Michael Ferguson
autogenerated on Sat Apr 27 2019 03:12:11