Classes | Enumerations | Functions
katana_450_6m90a_kinematics Namespace Reference

Classes

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, 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)
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 IKcos (float f)
double IKcos (double f)
 IKFAST_COMPILE_ASSERT (IKFAST_VERSION==61)
float IKfmod (float x, float y)
double IKfmod (double x, double y)
float IKlog (float f)
double IKlog (double f)
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

IKP_TranslationXY2D 

2D translation along XY plane

direction. Can be thought of as Ray IK where the origin of the ray must coincide.

IKP_TranslationXYOrientation3D 

2D translation along XY plane and 1D rotation around Z axis. The

IKP_TranslationLocalGlobal6D 

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

offset of the rotation is measured starting at +X, so at +X is it 0, at +Y it is pi/2.

IKP_TranslationXAxisAngle4D 

end effector origin reaches desired 3D translation, manipulator

IKP_TranslationYAxisAngle4D 

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) end effector origin reaches desired 3D translation, manipulator

IKP_TranslationZAxisAngle4D 

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) end effector origin reaches desired 3D translation, manipulator

IKP_TranslationXAxisAngleZNorm4D 

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. end effector origin reaches desired 3D translation, manipulator

IKP_TranslationYAxisAngleXNorm4D 

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) end effector origin reaches desired 3D translation, manipulator

IKP_TranslationZAxisAngleYNorm4D 

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) end effector origin reaches desired 3D translation, manipulator

IKP_NumberOfParameterizations 

number of parameterizations (does not count IKP_None)

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_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

Definition at line 72 of file katana_450_6m90a_ikfast_plugin.cpp.


Function Documentation

IKFAST_API void katana_450_6m90a_kinematics::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 211 of file katana_450_6m90a_ikfast_plugin.cpp.

IKFAST_API bool katana_450_6m90a_kinematics::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 1472 of file katana_450_6m90a_ikfast_plugin.cpp.

void katana_450_6m90a_kinematics::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 katana_450_6m90a_kinematics::dgesv_ ( const int *  n,
const int *  nrhs,
double *  a,
const int *  lda,
int *  ipiv,
double *  b,
const int *  ldb,
int *  info 
)
void katana_450_6m90a_kinematics::dgetrf_ ( const int *  m,
const int *  n,
double *  a,
const int *  lda,
int *  ipiv,
int *  info 
)
void katana_450_6m90a_kinematics::dgetri_ ( const int *  n,
const double *  a,
const int *  lda,
int *  ipiv,
double *  work,
const int *  lwork,
int *  info 
)
void katana_450_6m90a_kinematics::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 254 of file katana_450_6m90a_ikfast_plugin.cpp.

Definition at line 1479 of file katana_450_6m90a_ikfast_plugin.cpp.

Definition at line 257 of file katana_450_6m90a_ikfast_plugin.cpp.

Definition at line 259 of file katana_450_6m90a_ikfast_plugin.cpp.

Definition at line 1477 of file katana_450_6m90a_ikfast_plugin.cpp.

Definition at line 253 of file katana_450_6m90a_ikfast_plugin.cpp.

Definition at line 255 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 89 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 90 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 146 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 153 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 113 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 120 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 168 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 178 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 162 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 163 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 129 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 138 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 95 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 96 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 189 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 199 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 160 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 161 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 92 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 93 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 166 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 167 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 164 of file katana_450_6m90a_ikfast_plugin.cpp.

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

Definition at line 165 of file katana_450_6m90a_ikfast_plugin.cpp.

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


katana_moveit_ikfast_plugin
Author(s): Martin Günther
autogenerated on Mon Aug 14 2017 02:43:58