Classes | Typedefs | Functions
opw_kinematics Namespace Reference

Classes

struct  Parameters
 

Typedefs

template<typename T >
using Transform = Eigen::Transform< T, 3, Eigen::Isometry >
 

Functions

template<typename T >
 DEPRECATED ("UN-TESTED") Parameters< T > makeFanucR2000iB_200R()
 
template<typename T >
Transform< T > forward (const Parameters< T > &p, const T *qs) noexcept
 Computes the tool pose of the robot described by when said robot has the joint positions given by qs, a 6 element array of type T. More...
 
template<typename T >
void harmonizeTowardZero (T *qs)
 
template<typename T >
void inverse (const Parameters< T > &params, const Transform< T > &pose, T *out) noexcept
 Computes up to 8 kinematically unique joint solutions that put the tool flange of the robot described by params at the pose given by pose. Results are stored in out, a 6x8 array of T. See out's description for more details. More...
 
template<typename T >
bool isValid (const T *qs)
 
template<typename T >
Parameters< T > makeIrb2400_10 ()
 
template<typename T >
Parameters< T > makeKukaKR6_R700_sixx ()
 
template<typename T >
std::ostream & operator<< (std::ostream &os, const Parameters< T > &params)
 

Typedef Documentation

template<typename T >
using opw_kinematics::Transform = typedef Eigen::Transform<T, 3, Eigen::Isometry>

Typedef equivalent to Eigen::Isometry3d for T = double and Eigen::Isometry3f for T = float.

Definition at line 15 of file opw_kinematics.h.

Function Documentation

template<typename T >
opw_kinematics::DEPRECATED ( "UN-TESTED"  )

Definition at line 29 of file opw_parameters_examples.h.

template<typename T >
Transform<T> opw_kinematics::forward ( const Parameters< T > &  p,
const T *  qs 
)
noexcept

Computes the tool pose of the robot described by when said robot has the joint positions given by qs, a 6 element array of type T.

Parameters
pThe robot for which you want to solve forward kinematics.
qsThe joint pose of the robot which you want to know the tool pose of.
Returns
The flange pose.
template<typename T >
void opw_kinematics::harmonizeTowardZero ( T *  qs)
inline

Definition at line 17 of file opw_utilities.h.

template<typename T >
void opw_kinematics::inverse ( const Parameters< T > &  params,
const Transform< T > &  pose,
T *  out 
)
noexcept

Computes up to 8 kinematically unique joint solutions that put the tool flange of the robot described by params at the pose given by pose. Results are stored in out, a 6x8 array of T. See out's description for more details.

Parameters
poseThe pose of the tool flange for which you want joint solutions for
paramsThe robot for which you want to solve.
outA pointer to an array of 48 elements (6x8). Values 0-5 will have the joint values of the first solution, 6-11 will have the second and so on. ALL 8 SOLUTIONS ARE ALWAYS WRITTEN, EVEN IF THEY CONTAIN NANS. You must check in a subsequent call if you have a solution. The plus side is that the first solution should be from the same configuraton each time.
template<typename T >
bool opw_kinematics::isValid ( const T *  qs)
inline

Definition at line 10 of file opw_utilities.h.

template<typename T >
Parameters<T> opw_kinematics::makeIrb2400_10 ( )

Definition at line 12 of file opw_parameters_examples.h.

template<typename T >
Parameters<T> opw_kinematics::makeKukaKR6_R700_sixx ( )

Definition at line 47 of file opw_parameters_examples.h.

template<typename T >
std::ostream& opw_kinematics::operator<< ( std::ostream &  os,
const Parameters< T > &  params 
)

Definition at line 11 of file opw_io.h.



moveit_opw_kinematics_plugin
Author(s): Jeroen De Maeyer, Simon Schmeisser (isys vision)
autogenerated on Wed Jun 3 2020 03:17:14