Simox  2.3.74.0
VirtualRobot::Grasp Class Reference
Inheritance diagram for VirtualRobot::Grasp:
VirtualRobot::ChainedGrasp

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Grasp (const std::string &name, const std::string &robotType, const std::string &eef, const Eigen::Matrix4f &poseInTCPCoordSystem, const std::string &creation="", float quality=0.0f, const std::string &eefPreshape="")
 
virtual ~Grasp ()
 
virtual void print (bool printDecoration=true) const
 
void setName (const std::string &name)
 
void setPreshape (const std::string &preshapeName)
 
Eigen::Matrix4f getTargetPoseGlobal (RobotPtr robot) const
 
Eigen::Matrix4f getTcpPoseGlobal (const Eigen::Matrix4f &objectPose) const
 
Eigen::Matrix4f getTcpPoseRobotRoot (const Eigen::Matrix4f &objectPose, const RobotPtr &robot) const
 
Eigen::Matrix4f getObjectTargetPoseGlobal (const Eigen::Matrix4f &graspingPose) const
 
void setTransformation (const Eigen::Matrix4f &tcp2Object)
 
std::string getName () const
 
std::string getRobotType () const
 
std::string getEefName () const
 
std::string getCreationMethod () const
 
std::string getPreshapeName () const
 
float getQuality () const
 
void setQuality (float q)
 
virtual Eigen::Matrix4f getTransformation () const
 
std::string toXML (int tabs=2) const
 
virtual GraspPtr clone () const
 
std::map< std::string, float > getConfiguration () const
 Returns the (optionally) stored configuration of the fingers / actors. More...
 
void setConfiguration (const std::map< std::string, float > &config)
 Optionally the configuration of the fingers / actors can be stored. More...
 

Protected Member Functions

virtual std::string getTransformationXML (const std::string &tabs) const
 

Protected Attributes

std::map< std::string, float > eefConfiguration
 Optional: the configuration of the actors. More...
 
Eigen::Matrix4f poseTcp
 The pose in TCP's coordinate system. More...
 
std::string robotType
 
std::string eef
 The eef specifies which TCP node should be used. More...
 
std::string name
 
std::string creation
 
float quality
 
std::string preshape
 Optionally an eef-preshape can be defined. More...
 

Detailed Description

A grasp is mainly specified by a TCP to object transformation.

Constructor & Destructor Documentation

◆ Grasp()

VirtualRobot::Grasp::Grasp ( const std::string &  name,
const std::string &  robotType,
const std::string &  eef,
const Eigen::Matrix4f &  poseInTCPCoordSystem,
const std::string &  creation = "",
float  quality = 0.0f,
const std::string &  eefPreshape = "" 
)

Constructor

Parameters
nameThe name of this grasp.
robotTypeThe robot type for which this grasp is defined.
eefThe end effector name.
poseInTCPCoordSystemThe pose of the object, given in eef's tcp coordinate system
creationA custom string explaining how the grasp was created.
qualityA custom quality index.
eefPreshapeAn optional preshape.

◆ ~Grasp()

VirtualRobot::Grasp::~Grasp ( )
virtualdefault

Member Function Documentation

◆ clone()

VirtualRobot::GraspPtr VirtualRobot::Grasp::clone ( ) const
virtual

Reimplemented in VirtualRobot::ChainedGrasp.

◆ getConfiguration()

std::map< std::string, float > VirtualRobot::Grasp::getConfiguration ( ) const

Returns the (optionally) stored configuration of the fingers / actors.

◆ getCreationMethod()

std::string VirtualRobot::Grasp::getCreationMethod ( ) const

◆ getEefName()

std::string VirtualRobot::Grasp::getEefName ( ) const

◆ getName()

std::string VirtualRobot::Grasp::getName ( ) const

◆ getObjectTargetPoseGlobal()

Eigen::Matrix4f VirtualRobot::Grasp::getObjectTargetPoseGlobal ( const Eigen::Matrix4f &  graspingPose) const

The returned pose is the object pose that have to be set in order to apply a grasp at pose graspingPose.

◆ getPreshapeName()

std::string VirtualRobot::Grasp::getPreshapeName ( ) const

◆ getQuality()

float VirtualRobot::Grasp::getQuality ( ) const

◆ getRobotType()

std::string VirtualRobot::Grasp::getRobotType ( ) const

◆ getTargetPoseGlobal()

Eigen::Matrix4f VirtualRobot::Grasp::getTargetPoseGlobal ( RobotPtr  robot) const

Get the (current) global pose of the target object when the grasp is applied on the corresponding EEF of robot. Note, that this pose is only valid for the current configuration of the robot. When the robot moves, the grasping pose will change, and you have to call this method again.

◆ getTcpPoseGlobal()

Eigen::Matrix4f VirtualRobot::Grasp::getTcpPoseGlobal ( const Eigen::Matrix4f &  objectPose) const

Get the global pose that has to be achieved by the tcp in order to apply the grasp on the object at position objectPose.

◆ getTcpPoseRobotRoot()

Eigen::Matrix4f VirtualRobot::Grasp::getTcpPoseRobotRoot ( const Eigen::Matrix4f &  objectPose,
const RobotPtr robot 
) const

Get the pose (relative to the robot root) that has to be achieved by the tcp in order to apply the grasp on the object at position objectPose.

◆ getTransformation()

Eigen::Matrix4f VirtualRobot::Grasp::getTransformation ( ) const
virtual

Return the transformation of this grasp. The transformation is given in the coordinate system of the tcp (whereas the tcp belongs to the eef). This transformation specifies the tcp to object relation (object in tcp frame).

Reimplemented in VirtualRobot::ChainedGrasp.

◆ getTransformationXML()

std::string VirtualRobot::Grasp::getTransformationXML ( const std::string &  tabs) const
protectedvirtual

Reimplemented in VirtualRobot::ChainedGrasp.

◆ print()

void VirtualRobot::Grasp::print ( bool  printDecoration = true) const
virtual

Reimplemented in VirtualRobot::ChainedGrasp.

◆ setConfiguration()

void VirtualRobot::Grasp::setConfiguration ( const std::map< std::string, float > &  config)

Optionally the configuration of the fingers / actors can be stored.

◆ setName()

void VirtualRobot::Grasp::setName ( const std::string &  name)

◆ setPreshape()

void VirtualRobot::Grasp::setPreshape ( const std::string &  preshapeName)

◆ setQuality()

void VirtualRobot::Grasp::setQuality ( float  q)

◆ setTransformation()

void VirtualRobot::Grasp::setTransformation ( const Eigen::Matrix4f &  tcp2Object)

Set the transformation of this grasp. The transformation is given in the coordinate system of the tcp (whereas the tcp belongs to the eef).

Parameters
tcp2ObjectThe transformation specifies the tcp to object relation.

◆ toXML()

std::string VirtualRobot::Grasp::toXML ( int  tabs = 2) const

Field Documentation

◆ creation

std::string VirtualRobot::Grasp::creation
protected

◆ eef

std::string VirtualRobot::Grasp::eef
protected

The eef specifies which TCP node should be used.

◆ eefConfiguration

std::map< std::string, float > VirtualRobot::Grasp::eefConfiguration
protected

Optional: the configuration of the actors.

◆ name

std::string VirtualRobot::Grasp::name
protected

◆ poseTcp

Eigen::Matrix4f VirtualRobot::Grasp::poseTcp
protected

The pose in TCP's coordinate system.

◆ preshape

std::string VirtualRobot::Grasp::preshape
protected

Optionally an eef-preshape can be defined.

◆ quality

float VirtualRobot::Grasp::quality
protected

◆ robotType

std::string VirtualRobot::Grasp::robotType
protected