Struct representing the DH parameters of a single transformation between adjacent links. This struct follows the classical DH parameter convention: Trans[Zi-1](d) * Rot[Zi-1](theta) * Trans[Xi](r) * Rot[Xi](alpha) See for reference.
#include <dh_chain.h>
|
| DHTransform (const Eigen::Vector4d ¶ms_, DHJointType type_) |
|
| DHTransform (const Eigen::Vector4d ¶ms_, DHJointType type_, const std::string &name_) |
|
| DHTransform (const Eigen::Vector4d ¶ms_, DHJointType type_, const std::string &name_, std::size_t random_seed) |
|
template<typename T > |
Isometry3< T > | createRelativeTransform (const T joint_value, const Eigen::Matrix< T, 1, 4 > &offsets) const |
| Creates the homogoneous transformation from the previous link to the current link.
|
|
template<typename T > |
Isometry3< T > | createRelativeTransform (const T joint_value) const |
| Creates the homogoneous transformation from the previous link to the current link without applying DH parameter offsets.
|
|
double | createRandomJointValue () const |
|
std::array< std::string, 4 > | getParamLabels () const |
|
|
Eigen::Vector4d | params |
| DH parameters d: The linear offset in Z theta: The rotational offset about Z r: The linear offset in X alpha: The rotational offset about X.
|
|
DHJointType | type |
| The type of actuation of the joint.
|
|
double | max = M_PI |
| Joint maximum value.
|
|
double | min = -M_PI |
| Joint minimum value.
|
|
std::string | name |
| Label for this transform.
|
|
std::size_t | random_seed |
| Seed for random number generator.
|
|
|
struct | YAML::as_if< DHTransform, void > |
|
◆ createRelativeTransform() [1/2]
template<typename T >
Isometry3< T > industrial_calibration::DHTransform::createRelativeTransform |
( |
const T |
joint_value, |
|
|
const Eigen::Matrix< T, 1, 4 > & |
offsets |
|
) |
| const |
|
inline |
- Parameters
-
joint_value | - The joint value to apply when caluclating the transform |
offsets | - The DH parameter offsets to apply when calculating the transform |
- Returns
◆ createRelativeTransform() [2/2]
template<typename T >
Isometry3< T > industrial_calibration::DHTransform::createRelativeTransform |
( |
const T |
joint_value | ) |
const |
|
inline |
- Parameters
-
joint_value | - The joint value to apply when calculating the transform |
- Returns