Industrial Calibration  1.0.0
Loading...
Searching...
No Matches
industrial_calibration::DHChain Class Reference

Robot representation using DH parameters.

#include <dh_chain.h>

Public Member Functions

 DHChain (std::vector< DHTransform > transforms, const Eigen::Isometry3d &base_offset=Eigen::Isometry3d::Identity())
 
 DHChain (const DHChain &rhs, const Eigen::MatrixX4d &dh_offsets)
 
template<typename T >
Isometry3< T > getFK (const Eigen::Matrix< T, Eigen::Dynamic, 1 > &joint_values) const
 Calculates forward kinematics for the chain with the joints provided. Note: the transform to the n-th link is calculated, where n is the size of joint_values.
 
template<typename T >
Isometry3< T > getFK (const Eigen::Matrix< T, Eigen::Dynamic, 1 > &joint_values, const Eigen::Matrix< T, Eigen::Dynamic, 4 > &offsets) const
 Calculates the forward kinematics for the chain given a set of joint values and DH parameter offsets Note: the transform to the n-th link is calculated, where n is the size of joint_values.
 
Eigen::VectorXd createUniformlyRandomPose () const
 Creates a random joint pose by choosing a random uniformly distributed joint value for each joint in the chain.
 
std::size_t dof () const
 Returns the number of degrees of freedom (i.e. DH transforms) of the chain.
 
Eigen::MatrixX4d getDHTable () const
 Gets a dof() x 4 matrix of the DH parameters.
 
std::vector< DHJointTypegetJointTypes () const
 Returns a the joint types of the kinematic chain in order.
 
std::vector< std::array< std::string, 4 > > getParamLabels () const
 Returns the labels of the DH parameters for each DH transform in the chain.
 
Eigen::Isometry3d getBaseOffset () const
 Gets the base offset of the transform.
 
Eigen::Isometry3d getRelativeTransform (int joint_index, double value) const
 Get a joints relative joint transform.
 

Protected Attributes

std::vector< DHTransformtransforms_
 The DH transforms that make up the chain.
 
Eigen::Isometry3d base_offset_
 Fixed transform offset to the beginning of the chain.
 

Friends

struct YAML::convert< DHChain >
 
struct YAML::as_if< DHChain, void >
 

Member Function Documentation

◆ getFK() [1/2]

template<typename T >
Isometry3< T > industrial_calibration::DHChain::getFK ( const Eigen::Matrix< T, Eigen::Dynamic, 1 > &  joint_values) const
inline
Parameters
joint_values- The joint values with which to calculate forward kinematics (size: [<= dof()])
Returns
Exceptions
Exceptionif the size of joint values is larger than the number of DH transforms in the chain

◆ getFK() [2/2]

template<typename T >
Isometry3< T > industrial_calibration::DHChain::getFK ( const Eigen::Matrix< T, Eigen::Dynamic, 1 > &  joint_values,
const Eigen::Matrix< T, Eigen::Dynamic, 4 > &  offsets 
) const
inline
Parameters
joint_values- The joint values with which to calculate the forward kinematics (size: [<= dof()])
offsets- The DH parameter offsets to apply when calculating the forward kinematics (size: [dof() x 4])
Returns
Exceptions
Exceptionif the size of joint_values is larger than the number of DH transforms in the chain or if the size of joint_values is larger than the rows of DH offsets

◆ createUniformlyRandomPose()

Eigen::VectorXd industrial_calibration::DHChain::createUniformlyRandomPose ( ) const
Returns

◆ dof()

std::size_t industrial_calibration::DHChain::dof ( ) const
Returns

◆ getDHTable()

Eigen::MatrixX4d industrial_calibration::DHChain::getDHTable ( ) const
Returns

◆ getJointTypes()

std::vector< DHJointType > industrial_calibration::DHChain::getJointTypes ( ) const
Returns

◆ getParamLabels()

std::vector< std::array< std::string, 4 > > industrial_calibration::DHChain::getParamLabels ( ) const
Returns

◆ getBaseOffset()

Eigen::Isometry3d industrial_calibration::DHChain::getBaseOffset ( ) const
Returns

◆ getRelativeTransform()

Eigen::Isometry3d industrial_calibration::DHChain::getRelativeTransform ( int  joint_index,
double  value 
) const
Parameters
joint_indexThe joint index
valueThe joint value
Returns
The joint relative transform