Public Types | Public Member Functions | Private Member Functions | Private Attributes
urdf2graspit::Urdf2GraspIt Class Reference

This class provides functions to transform a robot described in URDF to its description in the GraspIt! format. More...

#include <Urdf2Graspit.h>

Inheritance diagram for urdf2graspit::Urdf2GraspIt:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
urdf2graspit::ConversionParameters 
GraspItConversionParameters
typedef
baselib_binding::shared_ptr
< GraspItConversionParameters >
::type 
GraspItConversionParametersPtr
typedef
urdf2graspit::ConversionResult 
GraspItConversionResult
typedef
baselib_binding::shared_ptr
< GraspItConversionResult >
::type 
GraspItConversionResultPtr

Public Member Functions

bool getDHParams (std::vector< DHParam > &dhparams, const std::string &fromLinkName) const
ConversionResultPtr processAll (const std::string &urdfFilename, const std::string &rootLinkName, const std::vector< std::string > &fingerRootNames, const std::string &material, const EigenTransform &addVisualTransform)
bool toDenavitHartenberg (const std::string &fromLink)
 Urdf2GraspIt (UrdfTraverserPtr &traverser, float _scaleFactor=1000, bool _negateJointMoves=false)
 ~Urdf2GraspIt ()

Private Member Functions

bool checkConversionPrerequisites (const GraspItConversionParametersPtr &param) const
bool getDHParams (std::vector< DHParam > &dhparameters, const JointConstPtr &joint, const EigenTransform &parentWorldTransform, const Eigen::Vector3d &parentX, const Eigen::Vector3d &parentZ, const Eigen::Vector3d &parentPos, bool asRootJoint, EigenTransform &parentWorldTransformDH) const
bool getDHParams (std::vector< DHParam > &dhparameters, const LinkConstPtr &from_link) const
bool getDHTransform (const JointPtr &joint, const std::vector< DHParam > &dh, EigenTransform &result) const
void getGlobalCoordinates (const JointConstPtr &joint, const EigenTransform &parentWorldTransform, Eigen::Vector3d &rotationAxis, Eigen::Vector3d &position) const
void getJointMoves (const urdf::Joint &j, float &velocity, float &effort)
void getLimits (const urdf::Joint &j, float &min, float &max)
std::string getWorldFileTemplate (const std::string &robotName, const std::vector< DHParam > &dhparams, const std::string &prependpath)
bool getXML (const std::vector< DHParam > &dhparams, const std::vector< std::string > &rootFingerJoints, const std::string &palmLinkName, const std::string *eigenXML, const std::string *contactsVGR, const std::string &mesh_pathprepend, std::string &result)
bool isContinuous (const JointPtr &joint) const
bool isPrismatic (const JointPtr &joint) const
bool isRevoluting (const JointPtr &joint) const
bool linksToDHReferenceFrames (const std::vector< DHParam > &dh)
virtual ConversionResultPtr postConvert (const ConversionParametersPtr &rootLink, ConversionResultPtr &result)
virtual ConversionResultPtr preConvert (const ConversionParametersPtr &params)
void printParams (const std::vector< DHParam > &dh) const
void scaleParams (std::vector< DHParam > &dh, double scale_factor) const
void toGlobalCoordinates (const EigenTransform &transform, const Eigen::Vector3d &input, Eigen::Vector3d &output)

Private Attributes

std::vector< DHParamdh_parameters
bool dhTransformed
bool isDHScaled
bool negateJointMoves

Detailed Description

This class provides functions to transform a robot described in URDF to its description in the GraspIt! format.

This requires a few steps:

  1. Conversion of all mesh formats into Inventor format
  2. Removal of fixed links in the URDF (fixed links are not fully supported by GraspIt! yet)
  3. Transformation of joint transforms such that the rotation axis is always z (to allow for conversion into Denavit-Hartenberg Parameters)
  4. Conversion of the joint transforms to the Denavit-Hartenberg convention.
  5. (optional) scaling of the model.
  6. Generate contact information for the hand model.
  7. Generation of all required xml and inventor files.
Author:
Jennifer Buehler

Definition at line 63 of file Urdf2Graspit.h.


Member Typedef Documentation

Definition at line 69 of file Urdf2Graspit.h.

Definition at line 70 of file Urdf2Graspit.h.

Definition at line 66 of file Urdf2Graspit.h.

Definition at line 67 of file Urdf2Graspit.h.


Constructor & Destructor Documentation

urdf2graspit::Urdf2GraspIt::Urdf2GraspIt ( UrdfTraverserPtr traverser,
float  _scaleFactor = 1000,
bool  _negateJointMoves = false 
) [inline, explicit]
Parameters:
_scaleFactorthe graspit model might have to be scaled (the urdf model is in meters, graspit! in millimeters). This can be specified with this scale factor.
_negateJointMovesnegates (inverts) joint limits and velocity/effort specified in URDF

Definition at line 78 of file Urdf2Graspit.h.

Definition at line 87 of file Urdf2Graspit.h.


Member Function Documentation

Definition at line 561 of file Urdf2Graspit.cpp.

bool Urdf2GraspIt::getDHParams ( std::vector< DHParam > &  dhparams,
const std::string &  fromLinkName 
) const

Returns the Denavit-Hartenberg parameters starting from the link fromLinkName. DH parameters are returned *for each child joint of fromLinkName*, where each child joint is going to be treated as a root joint starting at the origin.

TODO: Provide a function like this, and also toDenavitHartenberg(), which starts at one root joint instead. At the moment the existing solution is tailored for the needs to convert to GraspIt!, but the code can be changed relatively easily to start from a root joint.

This will only work if prepareModelForDenavitHartenberg() has been called before.

Definition at line 379 of file Urdf2Graspit.cpp.

bool Urdf2GraspIt::getDHParams ( std::vector< DHParam > &  dhparameters,
const JointConstPtr joint,
const EigenTransform parentWorldTransform,
const Eigen::Vector3d &  parentX,
const Eigen::Vector3d &  parentZ,
const Eigen::Vector3d &  parentPos,
bool  asRootJoint,
EigenTransform parentWorldTransformDH 
) const [private]

Returns the Denavit-Hartenberg parameters starting from the joint. This is a recursive function, so it will solve for the requested joint and then call itself on sub-branches

Parameters:
parentWorldTransformthe parent of this joint has this world transform.
parentXthe x-axis as determined by the call of this function for this joint's parent, or the root/global x axis for the first call (e.g. 1,0,0)
parentZthe z-axis (rotation axis) as determined by the call of this function for this joint's parent. If asRootJoint=true, the value will be ignored.
parentPosposition of parent as determined by the call of this function for this joint's parent, or the origin for the first call
asRootJointset to true for the first call of this function
parentWorldTransformDHresulting transformation in DH space at the end of the chain. This parameter is used in the recursion and should be the identity for root joints (asRootJoint = true).

Definition at line 205 of file Urdf2Graspit.cpp.

bool Urdf2GraspIt::getDHParams ( std::vector< DHParam > &  dhparameters,
const LinkConstPtr from_link 
) const [private]

Returns the Denavit-Hartenberg parameters starting from link from_link

Definition at line 355 of file Urdf2Graspit.cpp.

bool Urdf2GraspIt::getDHTransform ( const JointPtr joint,
const std::vector< DHParam > &  dh,
EigenTransform result 
) const [private]

Returns the transform in DH-space for this joint, as present in the dh parameters. Returns false if this joint is not represented in the dh parameters.

Definition at line 398 of file Urdf2Graspit.cpp.

void Urdf2GraspIt::getGlobalCoordinates ( const JointConstPtr joint,
const EigenTransform parentWorldTransform,
Eigen::Vector3d &  rotationAxis,
Eigen::Vector3d &  position 
) const [private]

Returns the joint transform in global coordinates, given that the world transform for the parent joint is parentWorldTransform. Both rotation axis and joint position are returned in global coordinates.

Definition at line 180 of file Urdf2Graspit.cpp.

void Urdf2GraspIt::getJointMoves ( const urdf::Joint &  j,
float &  velocity,
float &  effort 
) [private]

returns velocity and effort of this joint

Definition at line 757 of file Urdf2Graspit.cpp.

void Urdf2GraspIt::getLimits ( const urdf::Joint &  j,
float &  min,
float &  max 
) [private]

returns minimum / maximum limits of this joint. For revolute Joints values in degrees are returned, for prismatic values in mm.

Definition at line 735 of file Urdf2Graspit.cpp.

std::string Urdf2GraspIt::getWorldFileTemplate ( const std::string &  robotName,
const std::vector< DHParam > &  dhparams,
const std::string &  prependpath 
) [private]

Gets the XML content which has to go into the world file

Definition at line 768 of file Urdf2Graspit.cpp.

bool Urdf2GraspIt::getXML ( const std::vector< DHParam > &  dhparams,
const std::vector< std::string > &  rootFingerJoints,
const std::string &  palmLinkName,
const std::string *  eigenXML,
const std::string *  contactsVGR,
const std::string &  mesh_pathprepend,
std::string &  result 
) [private]

Reads robot information from the DH parameters and from the urdf and returns the GraspIt! XML file as string. Only hands with purely rigid DOF's (only type "r") supported so far. No fixed links are allowed in the URDF, remove them with joinFixedLinks().

Parameters:
dhparamsdh parameters for all joints starting from palmLinkName
rootFingerJointsa vector of names for the joints which start a finger
palmLinkNamethe name of the palm
mesh_pathprependpath to prepend to the <linkfilename>.xml file path specifications

Definition at line 45 of file Urdf2Graspit.cpp.

bool urdf2graspit::Urdf2GraspIt::isContinuous ( const JointPtr joint) const [inline, private]

Definition at line 229 of file Urdf2Graspit.h.

bool urdf2graspit::Urdf2GraspIt::isPrismatic ( const JointPtr joint) const [inline, private]

Definition at line 235 of file Urdf2Graspit.h.

bool urdf2graspit::Urdf2GraspIt::isRevoluting ( const JointPtr joint) const [inline, private]

Definition at line 223 of file Urdf2Graspit.h.

bool Urdf2GraspIt::linksToDHReferenceFrames ( const std::vector< DHParam > &  dh) [private]

Transforms all link's visuals, collisions and intertials according to the DH parameters. This is needed because the sequence of DH transforms is not equal to the sequence of URDF joint transforms. And the reference frame for a joint in DH parameters is acutally located at the next joint's position (and oriented according to the DH parameter). In URDF, a link is located in the current joint's reference frame as given in the joint's transform. However the link now has to be rooted in the DH reference frame, and oriented such that it ends up at the same global position as it would be when rooted in the URDF joint reference frame. Hence, we have to find for each joint the transform from the joint reference frame to the DH reference frame, and transform the visuals/collisions/intertials by it.

Definition at line 475 of file Urdf2Graspit.cpp.

Reimplemented from urdf2inventor::Urdf2Inventor.

Definition at line 655 of file Urdf2Graspit.cpp.

Reimplemented from urdf2inventor::Urdf2Inventor.

Definition at line 603 of file Urdf2Graspit.cpp.

void Urdf2GraspIt::printParams ( const std::vector< DHParam > &  dh) const [private]

Prints the DH parameters

Definition at line 517 of file Urdf2Graspit.cpp.

Urdf2GraspIt::ConversionResultPtr Urdf2GraspIt::processAll ( const std::string &  urdfFilename,
const std::string &  rootLinkName,
const std::vector< std::string > &  fingerRootNames,
const std::string &  material,
const EigenTransform addVisualTransform 
)

Convenience method which does all the operations required for the conversion. This method can be used as a template to create variations of this process. You may be interested in calling cleanup() after processing this in order to clean out temporary files which have been created.

a) join the links with fixed joints in the URDF, such that the model does not contain any more fixed joints. b) transform the model such that all rotation axises are the z-axis c) starts a viewer so the user can select contact points in the hand d) calls convert() to transform the model and generate XML files, and writes all necessary files.

Parameters:
urdfFilenameurdf file with the robot description.
rootLinkNamethe name of the link in the URDF which will be the root of the GraspIt! model. usually, this is the palm.
fingerRootNamesthe roots of all fingers in the hand (the names of the joints which are the first in each finger)
materialthe material to use in the converted format
addVisualTransformthis transform will be post-multiplied on all links' **visuals** (not links!) local transform (their "origin"). This can be used to correct transformation errors which may have been introduced in converting meshes from one format to the other, losing orientation information (for example, .dae has an "up vector" definition which may have been ignored)

Definition at line 777 of file Urdf2Graspit.cpp.

void Urdf2GraspIt::scaleParams ( std::vector< DHParam > &  dh,
double  scale_factor 
) const [private]

scales r and d parameters in dh by the given factor

Definition at line 507 of file Urdf2Graspit.cpp.

bool Urdf2GraspIt::toDenavitHartenberg ( const std::string &  fromLink)

Transforms the model to denavit hartenberg parameters, starting from the specified link. See also comments in getDHParams().

This method will change some transforms of joints/links and visuals/inertails/collisions. The model must have been transformed before with prepareModelForDenavitHartenberg()!

Definition at line 528 of file Urdf2Graspit.cpp.

void Urdf2GraspIt::toGlobalCoordinates ( const EigenTransform transform,
const Eigen::Vector3d &  input,
Eigen::Vector3d &  output 
) [private]
Return values:
-2on error
-1if the joint has multiple children
0if the joint has no child joints (it's an end effector joint),
1if a child joint is returned in parameter "child" Transforms a vector (input) within a local coordinate system (given by transform) into world coordinates

Definition at line 170 of file Urdf2Graspit.cpp.


Member Data Documentation

Definition at line 297 of file Urdf2Graspit.h.

Definition at line 295 of file Urdf2Graspit.h.

Definition at line 294 of file Urdf2Graspit.h.

Obsolete at this stage -- may be of use still in future. Returns the transform from DH space to standard kinematic chain space (as in URDF) for the joint (or vice versa, if dhToKin is set to false). It is necessary to specify the root of the chain of this joint (the root joint of the chain in which joint exists, specified relative to the global coordinate system). The root joint corresponds to the first joint in the DH-Parameters. The DH-parameters passed as parameter may contain several root joints, one for each chain.

Definition at line 293 of file Urdf2Graspit.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