Simox
2.3.74.0
|
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... | |
A grasp is mainly specified by a TCP to object transformation.
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
name | The name of this grasp. |
robotType | The robot type for which this grasp is defined. |
eef | The end effector name. |
poseInTCPCoordSystem | The pose of the object, given in eef's tcp coordinate system |
creation | A custom string explaining how the grasp was created. |
quality | A custom quality index. |
eefPreshape | An optional preshape. |
|
virtualdefault |
|
virtual |
Reimplemented in VirtualRobot::ChainedGrasp.
std::map< std::string, float > VirtualRobot::Grasp::getConfiguration | ( | ) | const |
Returns the (optionally) stored configuration of the fingers / actors.
std::string VirtualRobot::Grasp::getCreationMethod | ( | ) | const |
std::string VirtualRobot::Grasp::getEefName | ( | ) | const |
std::string VirtualRobot::Grasp::getName | ( | ) | const |
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.
std::string VirtualRobot::Grasp::getPreshapeName | ( | ) | const |
float VirtualRobot::Grasp::getQuality | ( | ) | const |
std::string VirtualRobot::Grasp::getRobotType | ( | ) | const |
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.
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.
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.
|
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.
|
protectedvirtual |
Reimplemented in VirtualRobot::ChainedGrasp.
|
virtual |
Reimplemented in VirtualRobot::ChainedGrasp.
void VirtualRobot::Grasp::setConfiguration | ( | const std::map< std::string, float > & | config | ) |
Optionally the configuration of the fingers / actors can be stored.
void VirtualRobot::Grasp::setName | ( | const std::string & | name | ) |
void VirtualRobot::Grasp::setPreshape | ( | const std::string & | preshapeName | ) |
void VirtualRobot::Grasp::setQuality | ( | float | q | ) |
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).
tcp2Object | The transformation specifies the tcp to object relation. |
std::string VirtualRobot::Grasp::toXML | ( | int | tabs = 2 | ) | const |
|
protected |
|
protected |
The eef specifies which TCP node should be used.
|
protected |
Optional: the configuration of the actors.
|
protected |
|
protected |
The pose in TCP's coordinate system.
|
protected |
Optionally an eef-preshape can be defined.
|
protected |
|
protected |