Simox  2.3.74.0
VirtualRobot::EndEffectorActor Class Reference
Inheritance diagram for VirtualRobot::EndEffectorActor:

Data Structures

struct  ActorDefinition
 

Public Types

enum  CollisionMode { eNone = 0, eActors = 1, eStatic = 2, eAll = 3 }
 

Public Member Functions

 EndEffectorActor (const std::string &name, const std::vector< ActorDefinition > &a, CollisionCheckerPtr colChecker=CollisionCheckerPtr())
 
std::vector< ActorDefinitiongetDefinition ()
 
EndEffectorActorPtr clone (RobotPtr newRobot)
 
std::string getName ()
 
bool moveActor (float angle=0.02)
 
bool moveActorCheckCollision (EndEffectorPtr eef, EndEffector::ContactInfoVector &storeContacts, SceneObjectSetPtr obstacles=SceneObjectSetPtr(), float angle=0.02)
 
bool isColliding (SceneObjectSetPtr obstacles, CollisionMode checkColMode=EndEffectorActor::eAll)
 
bool isColliding (EndEffectorPtr eef, SceneObjectSetPtr obstacles, EndEffector::ContactInfoVector &storeContacts, CollisionMode checkColMode=EndEffectorActor::eAll)
 
bool isColliding (SceneObjectPtr obstacle, CollisionMode checkColMode=EndEffectorActor::eAll)
 
bool isColliding (EndEffectorPtr eef, SceneObjectPtr obstacle, EndEffector::ContactInfoVector &storeContacts, CollisionMode checkColMode=EndEffectorActor::eAll)
 
bool isColliding (EndEffectorActorPtr obstacle)
 
bool isColliding (EndEffectorPtr eef, EndEffectorActorPtr obstacle, EndEffector::ContactInfoVector &storeContacts)
 
bool isColliding (EndEffectorPtr obstacle)
 
bool isColliding (EndEffectorPtr eef, EndEffectorPtr obstacle, EndEffector::ContactInfoVector &storeContacts)
 
std::vector< RobotNodePtrgetRobotNodes ()
 
void print ()
 
bool hasNode (RobotNodePtr node)
 
bool nodesSufficient (std::vector< RobotNodePtr > nodes) const
 Returns true, if nodes (only name strings are checked) are sufficient for building this eef. More...
 
float getApproximatedLength ()
 
RobotConfigPtr getConfiguration ()
 
virtual std::string toXML (int ident=1)
 
bool isAtHiLimit () const
 
bool isAtLoLimit () const
 

Member Enumeration Documentation

◆ CollisionMode

Enumerator
eNone 
eActors 
eStatic 
eAll 

Constructor & Destructor Documentation

◆ EndEffectorActor()

VirtualRobot::EndEffectorActor::EndEffectorActor ( const std::string &  name,
const std::vector< ActorDefinition > &  a,
CollisionCheckerPtr  colChecker = CollisionCheckerPtr() 
)

Member Function Documentation

◆ clone()

EndEffectorActorPtr VirtualRobot::EndEffectorActor::clone ( RobotPtr  newRobot)

Clones the EndEffectorActor with respect to the given robot. Note that unlike the clone-methods of RobotNodeSet and EndEffector, this method does not register anything with the robot.

◆ getApproximatedLength()

float VirtualRobot::EndEffectorActor::getApproximatedLength ( )

returns an approximation about the length of this eef.

◆ getConfiguration()

VirtualRobot::RobotConfigPtr VirtualRobot::EndEffectorActor::getConfiguration ( )

◆ getDefinition()

std::vector< EndEffectorActor::ActorDefinition > VirtualRobot::EndEffectorActor::getDefinition ( )

◆ getName()

std::string VirtualRobot::EndEffectorActor::getName ( )

◆ getRobotNodes()

std::vector< RobotNodePtr > VirtualRobot::EndEffectorActor::getRobotNodes ( )

◆ hasNode()

bool VirtualRobot::EndEffectorActor::hasNode ( RobotNodePtr  node)

Check, if node is part of this actor.

◆ isAtHiLimit()

bool VirtualRobot::EndEffectorActor::isAtHiLimit ( ) const

◆ isAtLoLimit()

bool VirtualRobot::EndEffectorActor::isAtLoLimit ( ) const

◆ isColliding() [1/8]

bool VirtualRobot::EndEffectorActor::isColliding ( SceneObjectSetPtr  obstacles,
CollisionMode  checkColMode = EndEffectorActor::eAll 
)

Checks if the actor collides with one of the given obstacles

◆ isColliding() [2/8]

bool VirtualRobot::EndEffectorActor::isColliding ( EndEffectorPtr  eef,
SceneObjectSetPtr  obstacles,
EndEffector::ContactInfoVector storeContacts,
CollisionMode  checkColMode = EndEffectorActor::eAll 
)

◆ isColliding() [3/8]

bool VirtualRobot::EndEffectorActor::isColliding ( SceneObjectPtr  obstacle,
CollisionMode  checkColMode = EndEffectorActor::eAll 
)

Checks if the actor collides with the given obstacle. checkColMode If set, the collisionMode of the actor's robotNodes is checked against it (e.g. to avoid collision checks with the static part of the eef)

◆ isColliding() [4/8]

bool VirtualRobot::EndEffectorActor::isColliding ( EndEffectorPtr  eef,
SceneObjectPtr  obstacle,
EndEffector::ContactInfoVector storeContacts,
CollisionMode  checkColMode = EndEffectorActor::eAll 
)

◆ isColliding() [5/8]

bool VirtualRobot::EndEffectorActor::isColliding ( EndEffectorActorPtr  obstacle)

Checks if the actor collides with a given second actor

◆ isColliding() [6/8]

bool VirtualRobot::EndEffectorActor::isColliding ( EndEffectorPtr  eef,
EndEffectorActorPtr  obstacle,
EndEffector::ContactInfoVector storeContacts 
)

◆ isColliding() [7/8]

bool VirtualRobot::EndEffectorActor::isColliding ( EndEffectorPtr  obstacle)

Checks if the actor collides with a given end effector

◆ isColliding() [8/8]

bool VirtualRobot::EndEffectorActor::isColliding ( EndEffectorPtr  eef,
EndEffectorPtr  obstacle,
EndEffector::ContactInfoVector storeContacts 
)

◆ moveActor()

bool VirtualRobot::EndEffectorActor::moveActor ( float  angle = 0.02)

Changes the value of all joints belonging to the actor by angle. Returns true if all joints hit their limit.

◆ moveActorCheckCollision()

bool VirtualRobot::EndEffectorActor::moveActorCheckCollision ( EndEffectorPtr  eef,
EndEffector::ContactInfoVector storeContacts,
SceneObjectSetPtr  obstacles = SceneObjectSetPtr(),
float  angle = 0.02 
)

Changes the value of all joints belonging to the actor by angle while checking every RobotNode for collisions with eef and obstacles.

Parameters
eefThe End effector
storeContactsIn case collisions are detected, the corresponding contact info is stored here.
obstaclesCheck collisions with these obstacles.
angleHow far should the eef actor move [rad] Returns true if all joints do either hit their limit or are in collision, e.g. the actor cannot be moved any further.

◆ nodesSufficient()

bool VirtualRobot::EndEffectorActor::nodesSufficient ( std::vector< RobotNodePtr nodes) const

Returns true, if nodes (only name strings are checked) are sufficient for building this eef.

◆ print()

void VirtualRobot::EndEffectorActor::print ( )

◆ toXML()

std::string VirtualRobot::EndEffectorActor::toXML ( int  ident = 1)
virtual