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 > ¶ms, 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 > ¶ms) |
| 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.
| 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.
| bool opw_kinematics::comparePoses | ( | const Eigen::Transform< T, 3, Eigen::Isometry > & | Ta, |
| const Eigen::Transform< T, 3, Eigen::Isometry > & | Tb, | ||
| T | tolerance | ||
| ) |
Definition at line 11 of file opw_kinematics_impl.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. |
Definition at line 34 of file opw_kinematics_impl.h.
|
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. |
Definition at line 113 of file opw_kinematics_impl.h.
|
inline |
Definition at line 10 of file opw_utilities.h.
| Parameters<T> opw_kinematics::makeFanucR2000iB_200R | ( | ) |
Definition at line 28 of file opw_parameters_examples.h.
| Parameters<T> opw_kinematics::makeIrb2400_10 | ( | ) |
Definition at line 10 of file opw_parameters_examples.h.
| Parameters<T> opw_kinematics::makeIrb2600_12_165 | ( | ) |
Definition at line 86 of file opw_parameters_examples.h.
| Parameters<T> opw_kinematics::makeIrb4600_60_205 | ( | ) |
Definition at line 105 of file opw_parameters_examples.h.
| Parameters<T> opw_kinematics::makeKukaKR6_R700_sixx | ( | ) |
Definition at line 46 of file opw_parameters_examples.h.
| Parameters<T> opw_kinematics::makeStaubliTX40 | ( | ) |
Definition at line 67 of file opw_parameters_examples.h.
| std::ostream& opw_kinematics::operator<< | ( | std::ostream & | os, |
| const Parameters< T > & | params | ||
| ) |