Classes | Typedefs | Functions
opw_kinematics Namespace Reference

Classes

struct  Parameters
 

Typedefs

template<typename T >
using Solutions = std::array< std::array< T, 6 >, 8 >
 
template<typename T >
using Transform = Eigen::Transform< T, 3, Eigen::Isometry >
 

Functions

template<typename T >
bool comparePoses (const Eigen::Transform< T, 3, Eigen::Isometry > &Ta, const Eigen::Transform< T, 3, Eigen::Isometry > &Tb, T tolerance)
 
template<typename T >
Transform< T > forward (const Parameters< T > &p, const std::array< T, 6 > &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 (std::array< T, 6 > &qs)
 
template<typename T >
Solutions< T > inverse (const Parameters< T > &params, const Transform< T > &pose) 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 std::array< T, 6 > &qs)
 
template<typename T >
Parameters< T > makeFanucR2000iB_200R ()
 
template<typename T >
Parameters< T > makeIrb2400_10 ()
 
template<typename T >
Parameters< T > makeIrb2600_12_165 ()
 
template<typename T >
Parameters< T > makeIrb4600_60_205 ()
 
template<typename T >
Parameters< T > makeKukaKR6_R700_sixx ()
 
template<typename T >
Parameters< T > makeStaubliTX40 ()
 
template<typename T >
std::ostream & operator<< (std::ostream &os, const Parameters< T > &params)
 

Typedef Documentation

◆ Solutions

template<typename T >
using opw_kinematics::Solutions = typedef std::array<std::array<T, 6>, 8>

Typedef equivalent to std::array<std::array<double, 6>, 8> for T = double and std::array<std::array<float, 6>, 8> for T = float.

Definition at line 22 of file opw_kinematics.h.

◆ Transform

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

◆ comparePoses()

template<typename T >
bool opw_kinematics::comparePoses ( const Eigen::Transform< T, 3, Eigen::Isometry > &  Ta,
const Eigen::Transform< T, 3, Eigen::Isometry > &  Tb,
tolerance 
)

Definition at line 11 of file opw_kinematics_impl.h.

◆ forward()

template<typename T >
Transform< T > opw_kinematics::forward ( const Parameters< T > &  p,
const std::array< T, 6 > &  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.

Definition at line 34 of file opw_kinematics_impl.h.

◆ harmonizeTowardZero()

template<typename T >
void opw_kinematics::harmonizeTowardZero ( std::array< T, 6 > &  qs)
inline

Definition at line 17 of file opw_utilities.h.

◆ inverse()

template<typename T >
Solutions< T > opw_kinematics::inverse ( const Parameters< T > &  params,
const Transform< T > &  pose 
)
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.
Returns
A array of 8 to an array of 6 elements. 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 configuration each time.

Definition at line 113 of file opw_kinematics_impl.h.

◆ isValid()

template<typename T >
bool opw_kinematics::isValid ( const std::array< T, 6 > &  qs)
inline

Definition at line 10 of file opw_utilities.h.

◆ makeFanucR2000iB_200R()

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

Definition at line 28 of file opw_parameters_examples.h.

◆ makeIrb2400_10()

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

Definition at line 10 of file opw_parameters_examples.h.

◆ makeIrb2600_12_165()

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

Definition at line 86 of file opw_parameters_examples.h.

◆ makeIrb4600_60_205()

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

Definition at line 105 of file opw_parameters_examples.h.

◆ makeKukaKR6_R700_sixx()

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

Definition at line 46 of file opw_parameters_examples.h.

◆ makeStaubliTX40()

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

Definition at line 67 of file opw_parameters_examples.h.

◆ operator<<()

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

Definition at line 10 of file opw_io.h.



opw_kinematics
Author(s): Jon Meyer , Jeroen De Maeyer
autogenerated on Thu Jan 16 2025 03:40:37