Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Private Member Functions | Friends
urdf2graspit::DHParam Class Reference

Class providing functions for conversion from urdf to a model described by denavit-hartenberg parameters. More...

#include <DHParam.h>

List of all members.

Public Types

typedef
urdf_traverser::EigenTransform 
EigenTransform
typedef
urdf_traverser::JointConstPtr 
JointConstPtr
typedef
urdf_traverser::LinkConstPtr 
LinkConstPtr

Public Member Functions

 DHParam ()
 DHParam (const DHParam &p)
DHParamoperator= (const DHParam &p)

Static Public Member Functions

static EigenTransform getTransform (const DHParam &p)
static bool getTransforms (const std::vector< DHParam > &dh, const bool dh2urdf, std::map< std::string, EigenTransform > &transforms)
static bool toDenavitHartenberg (DHParam &param, const Eigen::Vector3d &zi_1, const Eigen::Vector3d &xi_1, const Eigen::Vector3d &pi_1, const Eigen::Vector3d &zi, const Eigen::Vector3d &pi, Eigen::Vector3d &xi)

Public Attributes

double alpha
LinkConstPtr childLink
double d
int dof_index
JointConstPtr joint
double r
double theta

Static Private Member Functions

static bool getAlpha (const Eigen::Vector3d &zi_1, const Eigen::Vector3d &zi, const Eigen::Vector3d &pi_1, const Eigen::Vector3d &pi, const Eigen::Vector3d &xi, double &alpha)
static bool getCommonNormal (const Eigen::Vector3d &zi_1, const Eigen::Vector3d &zi, const Eigen::Vector3d &pi_1, const Eigen::Vector3d &pi, Eigen::Vector3d &commonNormal, Eigen::Vector3d &nOriginOnZi_1, double &shortestDistance, bool &parallel)
static bool getDAndTheta (const Eigen::Vector3d &zi_1, const Eigen::Vector3d &xi_1, const Eigen::Vector3d &pi_1, const Eigen::Vector3d &xi, const Eigen::Vector3d &normOriginOnZi_1, double &d, double &theta)
static EigenTransform getTransform (const urdf::Pose &p)
static EigenTransform getTransform (const DHParam::JointConstPtr &joint)

Friends

std::ostream & operator<< (std::ostream &o, const DHParam &p)

Detailed Description

Class providing functions for conversion from urdf to a model described by denavit-hartenberg parameters.

DH Parameters given in this class transform from a reference frame (i) to (i+1). The URDF joint is located at frame (i).

Author:
Jennifer Buehler
Date:
last edited October 2015

Definition at line 40 of file DHParam.h.


Member Typedef Documentation

Definition at line 43 of file DHParam.h.

Definition at line 44 of file DHParam.h.

Definition at line 45 of file DHParam.h.


Constructor & Destructor Documentation

Definition at line 47 of file DHParam.h.

urdf2graspit::DHParam::DHParam ( const DHParam p) [inline]

Definition at line 54 of file DHParam.h.


Member Function Documentation

bool DHParam::getAlpha ( const Eigen::Vector3d &  zi_1,
const Eigen::Vector3d &  zi,
const Eigen::Vector3d &  pi_1,
const Eigen::Vector3d &  pi,
const Eigen::Vector3d &  xi,
double &  alpha 
) [static, private]

Calcuates DH-Paramters r and alpha between to frames i-1 and i.

Parameters:
xithe common normal between frames i-1 and i (must be normalized, so it could be re-scaled to the length between frames by multiplying with r).
alphathe angle between both z-axises.
pi_1and p_i position in world coordinates of frames i-1 and i
zi_1and z_i z-axises of both frames i-1 and i

Definition at line 323 of file DHParam.cpp.

bool DHParam::getCommonNormal ( const Eigen::Vector3d &  zi_1,
const Eigen::Vector3d &  zi,
const Eigen::Vector3d &  pi_1,
const Eigen::Vector3d &  pi,
Eigen::Vector3d &  commonNormal,
Eigen::Vector3d &  nOriginOnZi_1,
double &  shortestDistance,
bool &  parallel 
) [static, private]

gets the common normal between zi_1 (through pi_1) and zi (through pi).

Parameters:
nOriginOnZi_1returns the point on zi_1 which is shortest from zi (this is intersection point if they intersect, or pi_1 if they are parallel)
shortestDistancethe length of the common normal, or also the shortest distance between the lines.
parallelreturns true if zi_1 and zi are parallel

Definition at line 518 of file DHParam.cpp.

bool DHParam::getDAndTheta ( const Eigen::Vector3d &  zi_1,
const Eigen::Vector3d &  xi_1,
const Eigen::Vector3d &  pi_1,
const Eigen::Vector3d &  xi,
const Eigen::Vector3d &  normOriginOnZi_1,
double &  d,
double &  theta 
) [static, private]
Parameters:
xinot only new x-axis, but also common normal between frames i-1 and i. Its origin is located along zi_1 and given in normOriginOnZi_1, such that xi from there points to frame i

Definition at line 361 of file DHParam.cpp.

Returns the transformation matrix for these DH parameters

Definition at line 617 of file DHParam.cpp.

DHParam::EigenTransform DHParam::getTransform ( const urdf::Pose &  p) [static, private]

Definition at line 665 of file DHParam.cpp.

Definition at line 680 of file DHParam.cpp.

bool DHParam::getTransforms ( const std::vector< DHParam > &  dh,
const bool  dh2urdf,
std::map< std::string, EigenTransform > &  transforms 
) [static]

For each child link defined in the DH parameters dh the transform the transform from DH to URDF space is returned in transforms. The transform is given in the local joint space.

Parameters:
transformsfor each link, the transform from DH to URDF space
Return values:
falseif there is a consistency error
Parameters:
dh2urdfif true, return transforms from DH to URDF. Otherwise, return it the other way round.

Definition at line 686 of file DHParam.cpp.

DHParam& urdf2graspit::DHParam::operator= ( const DHParam p) [inline]

Definition at line 73 of file DHParam.h.

bool DHParam::toDenavitHartenberg ( DHParam param,
const Eigen::Vector3d &  zi_1,
const Eigen::Vector3d &  xi_1,
const Eigen::Vector3d &  pi_1,
const Eigen::Vector3d &  zi,
const Eigen::Vector3d &  pi,
Eigen::Vector3d &  xi 
) [static]

Computes Denavit Hartenberg parameters.

Parameters:
zi_1z axis (rotation axis) in frame i-1
xi_1x axis (rotation axis) in frame i-1, obtained from previous calls to this function for joints earlier in the chain or any axis for root joint.
pi_1world position (global coordinates) in frame i-1, obtained from previous calls to this function for joints earlier in the chain (when returned as parameter pi), or for the root joint this is the position of the joint as given in URDF space (global coordinates).
ziz-axis of frame i.
piposition of the joint in frame i. This will be the global pose of the joint in URDF space.
xithe new x-axis of frame i will be returned in this paramter.

Definition at line 422 of file DHParam.cpp.


Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  o,
const DHParam p 
) [friend]

Definition at line 87 of file DHParam.h.


Member Data Documentation

Definition at line 71 of file DHParam.h.

Definition at line 66 of file DHParam.h.

Definition at line 68 of file DHParam.h.

Definition at line 67 of file DHParam.h.

Definition at line 65 of file DHParam.h.

Definition at line 69 of file DHParam.h.

Definition at line 70 of file DHParam.h.


The documentation for this class was generated from the following files:


urdf2graspit
Author(s): Jennifer Buehler
autogenerated on Wed May 8 2019 02:53:45