Classes | Public Member Functions | Protected Types | Protected Member Functions | Static Protected Member Functions | Private Member Functions | Private Attributes
urdf2graspit::ContactsGenerator Class Reference

Provides methods to generate contacts for GraspIt! including an interative viewer. More...

#include <ContactsGenerator.h>

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

List of all members.

Classes

class  Contact
 Helper class to encapsulate contact information. More...

Public Member Functions

 ContactsGenerator (UrdfTraverserPtr &traverser, float _scaleFactor=1000)
bool generateContacts (const std::vector< std::string > &rootFingerJoints, const std::string &palmLinkName, const float coefficient, const markerselector::MarkerSelector::MarkerMap &markers, const std::vector< DHParam > &dh)
bool generateContactsWithViewer (const std::vector< std::string > &fingerRoots, const std::string &palmLinkName, float standard_coefficient, const std::vector< DHParam > &dh, bool _displayAxes, bool _axesFromDH, float _axesRadius, float _axesLength, const EigenTransform &addVisualTransform, bool facesCCW)
std::string getContactsFileContent (const std::string &robotName)
 ~ContactsGenerator ()

Protected Types

typedef
baselib_binding::shared_ptr
< Contact >::type 
ContactPtr

Protected Member Functions

void applyTransformToContacts (LinkPtr &link, const EigenTransform &trans, bool preMult)
SoNode * getAxesAsInventor (const LinkPtr &from_link, const std::vector< DHParam > &dh, float _axesRadius, float _axesLength, bool linkIsRoot)
bool transformToDHReferenceFrames (const std::vector< DHParam > &dh)

Static Protected Member Functions

static bool getDHParam (const std::string jointName, const std::vector< DHParam > &dh, DHParam &jointDH)

Private Member Functions

bool generateContactsForallVisuals (const std::string &linkName, const int linkNum, const int fingerNum, const float coefficient, const std::vector< markerselector::MarkerSelector::Marker > &markers)
void scaleContacts (double scale_factor)

Private Attributes

std::vector< ContactPtrcontacts
bool isContactsScaled
std::map< std::string,
std::vector< ContactPtr > > 
linkContacts

Detailed Description

Provides methods to generate contacts for GraspIt! including an interative viewer.

Date:
March 2016
Author:
Jennifer Buehler

Definition at line 53 of file ContactsGenerator.h.


Member Typedef Documentation

typedef baselib_binding::shared_ptr<Contact>::type urdf2graspit::ContactsGenerator::ContactPtr [protected]

Definition at line 153 of file ContactsGenerator.h.


Constructor & Destructor Documentation

urdf2graspit::ContactsGenerator::ContactsGenerator ( UrdfTraverserPtr traverser,
float  _scaleFactor = 1000 
) [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.

Definition at line 60 of file ContactsGenerator.h.

Definition at line 66 of file ContactsGenerator.h.


Member Function Documentation

void ContactsGenerator::applyTransformToContacts ( LinkPtr link,
const EigenTransform trans,
bool  preMult 
) [protected]

Definition at line 75 of file ContactsGenerator.cpp.

bool ContactsGenerator::generateContacts ( const std::vector< std::string > &  rootFingerJoints,
const std::string &  palmLinkName,
const float  coefficient,
const markerselector::MarkerSelector::MarkerMap markers,
const std::vector< DHParam > &  dh 
)

Generates contacts file out of the markers defined in the map. This function is provided in case the markers information is obtained in a user-defined way. For an interactive marker generation, use function generateContactsWithViewer(). After contacts have been generated, they will be put into DH-space specified in dh.

**Careful**: This function will join fixed links in the loaded URDF, and will also change all rotation axes to be the z axis

Parameters:
markersa map with the markers.
coefficientContact friction coefficient

Definition at line 209 of file ContactsGenerator.cpp.

bool ContactsGenerator::generateContactsForallVisuals ( const std::string &  linkName,
const int  linkNum,
const int  fingerNum,
const float  coefficient,
const std::vector< markerselector::MarkerSelector::Marker > &  markers 
) [private]

Definition at line 111 of file ContactsGenerator.cpp.

bool ContactsGenerator::generateContactsWithViewer ( const std::vector< std::string > &  fingerRoots,
const std::string &  palmLinkName,
float  standard_coefficient,
const std::vector< DHParam > &  dh,
bool  _displayAxes,
bool  _axesFromDH,
float  _axesRadius,
float  _axesLength,
const EigenTransform addVisualTransform,
bool  facesCCW 
)

Starts a viewer in which the user may select contact points to be defined for the hand. The function generateContacts() is then called so that contacts are defined for the model.

Parameters:
_displayAxesadd the local coordinate system axes of the links to the inventor nodes to display. z axis is displayed blue, y axis green, x axis red.
_axesFromDHif true, then _displayAxes will display the DH reference frame axes, otherwise it will be the link reference frames in URDF.
_axesRadiusradius of the axes, if _addAxes is true
_axesLengthlength of the axes, if _addAxes is true
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)
facesCCWthe faces in the model are ordered counter-clockwise (true should be default)

Definition at line 472 of file ContactsGenerator.cpp.

SoNode * ContactsGenerator::getAxesAsInventor ( const LinkPtr from_link,
const std::vector< DHParam > &  dh,
float  _axesRadius,
float  _axesLength,
bool  linkIsRoot 
) [protected]

Definition at line 389 of file ContactsGenerator.cpp.

std::string ContactsGenerator::getContactsFileContent ( const std::string &  robotName)

Writes the file for the contacts. Will only work after generateContacts() has been called.

Definition at line 304 of file ContactsGenerator.cpp.

bool ContactsGenerator::getDHParam ( const std::string  jointName,
const std::vector< DHParam > &  dh,
DHParam jointDH 
) [static, protected]

Definition at line 459 of file ContactsGenerator.cpp.

void ContactsGenerator::scaleContacts ( double  scale_factor) [private]

scales the contacts by given factor

Definition at line 96 of file ContactsGenerator.cpp.

bool ContactsGenerator::transformToDHReferenceFrames ( const std::vector< DHParam > &  dh) [protected]

Definition at line 44 of file ContactsGenerator.cpp.


Member Data Documentation

Definition at line 180 of file ContactsGenerator.h.

Definition at line 178 of file ContactsGenerator.h.

std::map<std::string, std::vector<ContactPtr> > urdf2graspit::ContactsGenerator::linkContacts [private]

Definition at line 181 of file ContactsGenerator.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