cob3_arm_kinematics::cob3_2 Namespace Reference

Classes

class  IKSolution
class  IKSolver

Typedefs

typedef double IKReal

Functions

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 void fk (const IKReal *j, IKReal *eetrans, IKReal *eerot)
IKFAST_API int * getFreeParameters ()
IKFAST_API int getIKRealSize ()
IKFAST_API int getIKType ()
IKFAST_API const char * getKinematicsHash ()
IKFAST_API int getNumFreeParameters ()
IKFAST_API int getNumJoints ()
IKFAST_API bool ik (const IKReal *eetrans, const IKReal *eerot, const IKReal *pfree, std::vector< IKSolution > &vsolutions)
double IKabs (double f)
float IKabs (float f)
double IKacos (double f)
float IKacos (float f)
double IKasin (double f)
float IKasin (float f)
double IKatan2 (double fy, double fx)
float IKatan2 (float fy, float fx)
double IKcos (double f)
float IKcos (float f)
float IKfmod (double x, double y)
float IKfmod (float x, float y)
double IKlog (double f)
float IKlog (float f)
double IKsign (double f)
float IKsign (float f)
double IKsin (double f)
float IKsin (float f)
double IKsqrt (double f)
float IKsqrt (float f)
double IKtan (double f)
float IKtan (float f)
void zgetrf_ (const int *m, const int *n, std::complex< double > *a, const int *lda, int *ipiv, int *info)

Typedef Documentation

Definition at line 95 of file ikfast_kinematics_plugin.cpp.


Function Documentation

void cob3_arm_kinematics::cob3_2::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 cob3_arm_kinematics::cob3_2::dgesv_ ( const int *  n,
const int *  nrhs,
double *  a,
const int *  lda,
int *  ipiv,
double *  b,
const int *  ldb,
int *  info 
)
void cob3_arm_kinematics::cob3_2::dgetrf_ ( const int *  m,
const int *  n,
double *  a,
const int *  lda,
int *  ipiv,
int *  info 
)
void cob3_arm_kinematics::cob3_2::dgetri_ ( const int *  n,
const double *  a,
const int *  lda,
int *  ipiv,
double *  work,
const int *  lwork,
int *  info 
)
void cob3_arm_kinematics::cob3_2::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 void cob3_arm_kinematics::cob3_2::fk ( const IKReal j,
IKReal eetrans,
IKReal eerot 
)

solves the forward kinematics equations.

Parameters:
pfree is an array specifying the free joints of the chain.

Definition at line 244 of file ikfast_kinematics_plugin.cpp.

IKFAST_API int* cob3_arm_kinematics::cob3_2::getFreeParameters (  ) 

Definition at line 379 of file ikfast_kinematics_plugin.cpp.

IKFAST_API int cob3_arm_kinematics::cob3_2::getIKRealSize (  ) 

Definition at line 382 of file ikfast_kinematics_plugin.cpp.

IKFAST_API int cob3_arm_kinematics::cob3_2::getIKType (  ) 

Definition at line 384 of file ikfast_kinematics_plugin.cpp.

IKFAST_API const char* cob3_arm_kinematics::cob3_2::getKinematicsHash (  ) 

Definition at line 1460 of file ikfast_kinematics_plugin.cpp.

IKFAST_API int cob3_arm_kinematics::cob3_2::getNumFreeParameters (  ) 

Definition at line 378 of file ikfast_kinematics_plugin.cpp.

IKFAST_API int cob3_arm_kinematics::cob3_2::getNumJoints (  ) 

Definition at line 380 of file ikfast_kinematics_plugin.cpp.

IKFAST_API bool cob3_arm_kinematics::cob3_2::ik ( const IKReal eetrans,
const IKReal eerot,
const IKReal pfree,
std::vector< IKSolution > &  vsolutions 
)

solves the inverse kinematics equations.

Parameters:
pfree is an array specifying the free joints of the chain.

Definition at line 1455 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKabs ( double  f  )  [inline]

Definition at line 137 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKabs ( float  f  )  [inline]

Definition at line 136 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKacos ( double  f  )  [inline]

Definition at line 186 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKacos ( float  f  )  [inline]

Definition at line 179 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKasin ( double  f  )  [inline]

Definition at line 153 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKasin ( float  f  )  [inline]

Definition at line 146 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKatan2 ( double  fy,
double  fx 
) [inline]

Definition at line 211 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKatan2 ( float  fy,
float  fx 
) [inline]

Definition at line 201 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKcos ( double  f  )  [inline]

Definition at line 196 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKcos ( float  f  )  [inline]

Definition at line 195 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKfmod ( double  x,
double  y 
) [inline]

Definition at line 171 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKfmod ( float  x,
float  y 
) [inline]

Definition at line 162 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKlog ( double  f  )  [inline]

Definition at line 140 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKlog ( float  f  )  [inline]

Definition at line 139 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKsign ( double  f  )  [inline]

Definition at line 232 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKsign ( float  f  )  [inline]

Definition at line 222 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKsin ( double  f  )  [inline]

Definition at line 194 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKsin ( float  f  )  [inline]

Definition at line 193 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKsqrt ( double  f  )  [inline]

Definition at line 200 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKsqrt ( float  f  )  [inline]

Definition at line 199 of file ikfast_kinematics_plugin.cpp.

double cob3_arm_kinematics::cob3_2::IKtan ( double  f  )  [inline]

Definition at line 198 of file ikfast_kinematics_plugin.cpp.

float cob3_arm_kinematics::cob3_2::IKtan ( float  f  )  [inline]

Definition at line 197 of file ikfast_kinematics_plugin.cpp.

void cob3_arm_kinematics::cob3_2::zgetrf_ ( const int *  m,
const int *  n,
std::complex< double > *  a,
const int *  lda,
int *  ipiv,
int *  info 
)
 All Classes Namespaces Files Functions Variables Typedefs Defines


cob_manipulator
Author(s): Alexander Bubeck
autogenerated on Fri Jan 11 09:58:14 2013