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 > ¶ms, 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 > ¶ms) |
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.
opw_kinematics::DEPRECATED | ( | "UN-TESTED" | ) |
Definition at line 29 of file opw_parameters_examples.h.
|
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.
p | The robot for which you want to solve forward kinematics. |
qs | The joint pose of the robot which you want to know the tool pose of. |
|
inline |
Definition at line 17 of file opw_utilities.h.
|
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.
pose | The pose of the tool flange for which you want joint solutions for |
params | The robot for which you want to solve. |
out | A 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. |
|
inline |
Definition at line 10 of file opw_utilities.h.
Parameters<T> opw_kinematics::makeIrb2400_10 | ( | ) |
Definition at line 12 of file opw_parameters_examples.h.
Parameters<T> opw_kinematics::makeKukaKR6_R700_sixx | ( | ) |
Definition at line 47 of file opw_parameters_examples.h.
std::ostream& opw_kinematics::operator<< | ( | std::ostream & | os, |
const Parameters< T > & | params | ||
) |