Simox  2.3.74.0
VirtualRobot::Robot Class Referenceabstract
Inheritance diagram for VirtualRobot::Robot:
VirtualRobot::SceneObject VirtualRobot::LocalRobot

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Robot (const std::string &name, const std::string &type="")
 
 ~Robot () override
 
virtual void setRootNode (RobotNodePtr node)=0
 
virtual RobotNodePtr getRootNode () const =0
 
virtual void applyJointValues ()
 
virtual void setThreadsafe (bool)
 
template<typename T >
std::shared_ptr< T > getVisualization (SceneObject::VisualizationType visuType=SceneObject::Full, bool sensors=true)
 
void showStructure (bool enable, const std::string &type="")
 
void showCoordinateSystems (bool enable, const std::string &type="")
 
void showPhysicsInformation (bool enableCoM, bool enableInertial, VisualizationNodePtr comModel=VisualizationNodePtr()) override
 
void setupVisualization (bool showVisualization, bool showAttachedVisualizations) override
 
virtual std::string getName () const
 
virtual std::string getType () const
 
void setType (const std::string &type)
 
void setName (const std::string &name)
 
void print (bool printChildren=false, bool printDecoration=true) const override
 
void setUpdateVisualization (bool enable) override
 
void setUpdateCollisionModel (bool enable) override
 
std::shared_ptr< Robotshared_from_this () const
 
virtual RobotConfigPtr getConfig () const
 
virtual bool setConfig (RobotConfigPtr c)
 
virtual void registerRobotNode (RobotNodePtr node)=0
 
virtual void deregisterRobotNode (RobotNodePtr node)=0
 
virtual bool hasRobotNode (RobotNodePtr node) const =0
 
virtual bool hasRobotNode (const std::string &robotNodeName) const =0
 
virtual RobotNodePtr getRobotNode (const std::string &robotNodeName) const =0
 
virtual std::vector< RobotNodePtrgetRobotNodes () const
 
virtual std::vector< std::string > getRobotNodeNames () const
 
virtual void getRobotNodes (std::vector< RobotNodePtr > &storeNodes, bool clearVector=true) const =0
 
virtual void registerRobotNodeSet (RobotNodeSetPtr nodeSet)=0
 
virtual void deregisterRobotNodeSet (RobotNodeSetPtr nodeSet)=0
 
virtual bool hasRobotNodeSet (RobotNodeSetPtr nodeSet) const
 
virtual bool hasRobotNodeSet (const std::string &name) const =0
 
virtual RobotNodeSetPtr getRobotNodeSet (const std::string &nodeSetName) const =0
 
virtual std::vector< RobotNodeSetPtrgetRobotNodeSets () const
 
virtual std::vector< std::string > getRobotNodeSetNames () const
 
virtual void getRobotNodeSets (std::vector< RobotNodeSetPtr > &storeNodeSet) const =0
 
const NodeMappinggetNodeMapping () const
 
virtual void registerEndEffector (EndEffectorPtr endEffector)=0
 
virtual bool hasEndEffector (EndEffectorPtr endEffector) const
 
virtual bool hasEndEffector (const std::string &endEffectorName) const =0
 
virtual EndEffectorPtr getEndEffector (const std::string &endEffectorName) const =0
 
virtual std::vector< EndEffectorPtrgetEndEffectors () const
 
virtual void getEndEffectors (std::vector< EndEffectorPtr > &storeEEF) const =0
 
virtual std::vector< CollisionModelPtrgetCollisionModels () const
 
CollisionCheckerPtr getCollisionChecker () override
 
virtual void highlight (VisualizationPtr visualization, bool enable)
 
int getNumFaces (bool collisionModel=false) override
 
virtual void setGlobalPose (const Eigen::Matrix4f &globalPose, bool applyValues)=0
 Set the global pose of this robot. More...
 
void setGlobalPose (const Eigen::Matrix4f &globalPose) override
 
virtual Eigen::Matrix4f getGlobalPoseForRobotNode (const RobotNodePtr &node, const Eigen::Matrix4f &globalPoseNode) const
 Get the global pose of this robot so that the RobotNode node is at pose globalPoseNode. More...
 
virtual void setGlobalPoseForRobotNode (const RobotNodePtr &node, const Eigen::Matrix4f &globalPoseNode)
 Set the global pose of this robot so that the RobotNode node is at pose globalPoseNode. More...
 
virtual Eigen::Matrix4f getGlobalPositionForRobotNode (const RobotNodePtr &node, const Eigen::Vector3f &globalPositionNode) const
 Get the global position of this robot so that the RobotNode node is at position globalPoseNode. More...
 
virtual void setGlobalPositionForRobotNode (const RobotNodePtr &node, const Eigen::Vector3f &globalPositionNode)
 Set the global position of this robot so that the RobotNode node is at position globalPoseNode. More...
 
Eigen::Vector3f getCoMLocal () override
 Return center of mass of this robot in local coordinate frame. All RobotNodes of this robot are considered according to their mass. More...
 
Eigen::Vector3f getCoMGlobal () override
 Return Center of Mass of this robot in global coordinates. All RobotNodes of this robot are considered according to their mass. More...
 
virtual float getMass () const
 Return accumulated mass of this robot. More...
 
virtual RobotPtr extractSubPart (RobotNodePtr startJoint, const std::string &newRobotType, const std::string &newRobotName, bool cloneRNS=true, bool cloneEEFs=true, CollisionCheckerPtr collisionChecker=CollisionCheckerPtr(), float scaling=1.0f, bool preventCloningMeshesIfScalingIs1=false)
 
virtual RobotPtr clone (const std::string &name, CollisionCheckerPtr collisionChecker=CollisionCheckerPtr(), float scaling=1.0f, bool preventCloningMeshesIfScalingIs1=false)
 
virtual RobotPtr clone (CollisionCheckerPtr collisionChecker=CollisionCheckerPtr(), float scaling=1.0f, bool preventCloningMeshesIfScalingIs1=false)
 
virtual RobotPtr cloneScaling ()
 Clones this robot and keeps the current scaling for the robot and each robot node. More...
 
virtual void setFilename (const std::string &filename)
 Just storing the filename. More...
 
virtual std::string getFilename () const
 Retrieve the stored filename. More...
 
virtual ReadLockPtr getReadLock ()
 
virtual WriteLockPtr getWriteLock ()
 
virtual void setJointValue (RobotNodePtr rn, float jointValue)
 
virtual void setJointValue (const std::string &nodeName, float jointValue)
 
virtual void setJointValues (const std::map< std::string, float > &jointValues)
 
virtual std::map< std::string, float > getJointValues () const
 
virtual void setJointValues (const std::map< RobotNodePtr, float > &jointValues)
 
virtual void setJointValues (RobotNodeSetPtr rns, const std::vector< float > &jointValues)
 
virtual void setJointValues (const std::vector< RobotNodePtr > rn, const std::vector< float > &jointValues)
 
virtual void setJointValues (RobotNodeSetPtr rns, const Eigen::VectorXf &jointValues)
 
virtual void setJointValues (RobotConfigPtr config)
 
virtual void setJointValues (RobotNodeSetPtr rns, RobotConfigPtr config)
 
virtual void setJointValues (TrajectoryPtr trajectory, float t)
 
virtual BoundingBox getBoundingBox (bool collisionModel=true) const
 
virtual SensorPtr getSensor (const std::string &name) const
 
template<class SensorType >
std::shared_ptr< SensorType > getSensor (const std::string &name) const
 
virtual std::vector< SensorPtrgetSensors () const
 
template<class SensorType >
std::vector< std::shared_ptr< SensorType > > getSensors () const
 
virtual std::string toXML (const std::string &basePath=".", const std::string &modelPath="models", bool storeEEF=true, bool storeRNS=true, bool storeSensors=true, bool storeModelFiles=true) const
 
float getScaling () const
 
void setScaling (float scaling)
 
void inflateCollisionModel (float inflationInMM)
 Inflates the collision models of all robot nodes of this robot. Useful for motion planning with a safety margin. More...
 
bool getPropagatingJointValuesEnabled () const
 
void setPropagatingJointValuesEnabled (bool enabled)
 
void setPassive ()
 
bool isPassive () const
 
void registerNodeMapping (const NodeMapping &nodeMapping)
 
- Public Member Functions inherited from VirtualRobot::SceneObject
 SceneObject (const std::string &name, VisualizationNodePtr visualization=VisualizationNodePtr(), CollisionModelPtr collisionModel=CollisionModelPtr(), const Physics &p=Physics(), CollisionCheckerPtr colChecker=CollisionCheckerPtr())
 
virtual ~SceneObject ()
 
std::string getName () const
 
void setName (const std::string &name)
 
virtual Eigen::Matrix4f getGlobalPose () const
 
virtual Eigen::Vector3f getGlobalPosition () const
 
virtual Eigen::Matrix3f getGlobalOrientation () const
 
virtual Eigen::Matrix4f getGlobalPose (const Eigen::Matrix4f &localPose) const
 
virtual Eigen::Vector3f getGlobalPosition (const Eigen::Vector3f &localPosition) const
 
virtual Eigen::Vector3f getGlobalDirection (const Eigen::Vector3f &localDircetion) const
 
virtual Eigen::Matrix3f getGlobalOrientation (const Eigen::Matrix3f &localOrientation) const
 
virtual void setGlobalPoseNoChecks (const Eigen::Matrix4f &pose)
 
virtual CollisionModelPtr getCollisionModel ()
 
void setVisualization (VisualizationNodePtr visualization)
 
void setCollisionModel (CollisionModelPtr colModel)
 
virtual VisualizationNodePtr getVisualization (SceneObject::VisualizationType visuType=SceneObject::Full)
 
virtual bool initialize (SceneObjectPtr parent=SceneObjectPtr(), const std::vector< SceneObjectPtr > &children=std::vector< SceneObjectPtr >())
 
bool getUpdateVisualizationStatus ()
 
bool getUpdateCollisionModelStatus ()
 
virtual void showCoordinateSystem (bool enable, float scaling=1.0f, std::string *text=NULL, const std::string &visualizationType="")
 
virtual bool showCoordinateSystemState ()
 
virtual void showBoundingBox (bool enable, bool wireframe=false)
 
virtual bool ensureVisualization (const std::string &visualizationType="")
 
Eigen::Matrix4f toLocalCoordinateSystem (const Eigen::Matrix4f &poseGlobal) const
 
Eigen::Vector3f toLocalCoordinateSystemVec (const Eigen::Vector3f &positionGlobal) const
 
Eigen::Matrix4f toGlobalCoordinateSystem (const Eigen::Matrix4f &poseLocal) const
 
Eigen::Vector3f toGlobalCoordinateSystemVec (const Eigen::Vector3f &positionLocal) const
 
Eigen::Matrix4f getTransformationTo (const SceneObjectPtr otherObject) const
 
Eigen::Matrix4f getTransformationFrom (const SceneObjectPtr otherObject) const
 
Eigen::Matrix4f transformTo (const SceneObjectPtr otherObject, const Eigen::Matrix4f &poseInOtherCoordSystem)
 
Eigen::Vector3f transformTo (const SceneObjectPtr otherObject, const Eigen::Vector3f &positionInOtherCoordSystem)
 
void setCoMLocal (const Eigen::Vector3f &comLocal)
 Set a new position for the CoM of this bode. More...
 
float getMass () const
 
void setMass (float m)
 
Physics::SimulationType getSimulationType () const
 
void setSimulationType (Physics::SimulationType s)
 
Eigen::Matrix3f getInertiaMatrix ()
 
Eigen::Matrix3f getInertiaMatrix (const Eigen::Vector3f &shift)
 If the Inertia Matrix is given at the CoM, this function returns the Inertia Matrix at the parallel shifted coordinate system. The shift is done using the parallel axis theorem (https://en.wikipedia.org/wiki/Parallel_axis_theorem) More...
 
Eigen::Matrix3f getInertiaMatrix (const Eigen::Vector3f &shift, const Eigen::Matrix3f &rotation)
 
Eigen::Matrix3f getInertiaMatrix (const Eigen::Matrix4f &transform)
 
void setInertiaMatrix (const Eigen::Matrix3f &im)
 
float getFriction ()
 
void setFriction (float friction)
 
SceneObject::Physics getPhysics ()
 
std::vector< std::string > getIgnoredCollisionModels ()
 
template<typename T >
std::shared_ptr< T > getVisualization (SceneObject::VisualizationType visuType=SceneObject::Full)
 
void highlight (VisualizationPtr visualization, bool enable)
 
SceneObjectPtr clone (const std::string &name, CollisionCheckerPtr colChecker=CollisionCheckerPtr(), float scaling=1.0f) const
 
SceneObjectPtr clone (CollisionCheckerPtr colChecker=CollisionCheckerPtr(), float scaling=1.0f) const
 
virtual bool attachChild (SceneObjectPtr child)
 
virtual void detachChild (SceneObjectPtr child)
 
virtual bool hasChild (SceneObjectPtr child, bool recursive=false) const
 
virtual bool hasChild (const std::string &childName, bool recursive=false) const
 
virtual bool hasParent () const
 
virtual SceneObjectPtr getParent () const
 
virtual std::vector< SceneObjectPtrgetChildren () const
 
virtual void updatePose (bool updateChildren=true)
 Compute the global pose of this object. More...
 
virtual void copyPoseFrom (const SceneObjectPtr &other)
 
virtual bool saveModelFiles (const std::string &modelPath, bool replaceFilenames)
 
void setScaling (float scaling)
 
float getScaling ()
 
bool reloadVisualizationFromXML (bool useVisAsColModelIfMissing=true)
 
const std::string & getVisualizationModelXML () const
 

Static Public Attributes

static const RobotPtr NullPtr {nullptr}
 

Protected Member Functions

 Robot ()
 
void validateNodeMapping (const NodeMapping &nodeMapping) const
 
void createVisualizationFromCollisionModels ()
 
virtual void applyJointValuesNoLock ()
 It is assumed that the mutex is already set. More...
 
- Protected Member Functions inherited from VirtualRobot::SceneObject
virtual SceneObject_clone (const std::string &name, CollisionCheckerPtr colChecker=CollisionCheckerPtr(), float scaling=1.0f) const
 
virtual void detachedFromParent ()
 Parent detached this object. More...
 
virtual void attached (SceneObjectPtr parent)
 Parent attached this object. More...
 
virtual void updatePose (const Eigen::Matrix4f &parentPose, bool updateChildren=true)
 
std::string getFilenameReplacementVisuModel (const std::string standardExtension=".wrl")
 
std::string getFilenameReplacementColModel (const std::string standardExtension=".wrl")
 
 SceneObject ()
 
std::string getSceneObjectXMLString (const std::string &basePath, int tabs, const std::string &modelPathRelative="")
 basic data, used by Obstacle and ManipulationObject More...
 
virtual bool initializePhysics ()
 

Protected Attributes

std::string filename
 
std::string type
 
bool updateVisualization
 
std::recursive_mutex mutex
 
bool use_mutex
 
bool propagatingJointValuesEnabled = true
 
bool passive {false}
 
- Protected Attributes inherited from VirtualRobot::SceneObject
std::string name
 
bool initialized
 
Eigen::Matrix4f globalPose
 
std::vector< SceneObjectPtrchildren
 
SceneObjectWeakPtr parent
 
CollisionModelPtr collisionModel
 
std::string collisionModelXML
 
VisualizationNodePtr visualizationModel
 
std::string visualizationModelXML
 
std::filesystem::path basePath
 
bool updateVisualization
 
bool updateCollisionModel
 
Physics physics
 
CollisionCheckerPtr collisionChecker
 
float scaling = 1.0f
 

Friends

class RobotIO
 

Additional Inherited Members

- Public Types inherited from VirtualRobot::SceneObject
enum  VisualizationType { Full, Collision, CollisionData }
 
- Static Public Member Functions inherited from VirtualRobot::SceneObject
static Eigen::Matrix3f shiftInertia (const Eigen::Matrix3f inertiaMatrix, const Eigen::Vector3f &shift, float mass)
 The shift is done using the parallel axis theorem (https://en.wikipedia.org/wiki/Parallel_axis_theorem) More...
 

Detailed Description

This is the main object defining the kinematic structure of a robot.

See also
RobotIO, RobotNode, RobotNodeSet, EndEffector

Constructor & Destructor Documentation

◆ Robot() [1/2]

VirtualRobot::Robot::Robot ( const std::string &  name,
const std::string &  type = "" 
)

Constructor

Parameters
nameSpecifies the name of this instance.
typeSpecifies the type of the robot (e.g. multiple robots of the same type could exists with different names)

◆ ~Robot()

VirtualRobot::Robot::~Robot ( )
overridedefault

◆ Robot() [2/2]

VirtualRobot::Robot::Robot ( )
protecteddefault

Member Function Documentation

◆ applyJointValues()

void VirtualRobot::Robot::applyJointValues ( )
virtual

Update the transformations of all joints

◆ applyJointValuesNoLock()

void VirtualRobot::Robot::applyJointValuesNoLock ( )
protectedvirtual

It is assumed that the mutex is already set.

Can be called internally, when lock is already set.

Reimplemented in VirtualRobot::LocalRobot.

◆ clone() [1/2]

VirtualRobot::RobotPtr VirtualRobot::Robot::clone ( const std::string &  name,
CollisionCheckerPtr  collisionChecker = CollisionCheckerPtr(),
float  scaling = 1.0f,
bool  preventCloningMeshesIfScalingIs1 = false 
)
virtual

Clones this robot.

Parameters
nameThe new name.
collisionCheckerIf set, the returned robot is registered with this col checker, otherwise the CollisionChecker of the original robot is used.
scalingScale Can be set to create a scaled version of this robot. Scaling is applied on kinematic, visual, and collision data.

◆ clone() [2/2]

RobotPtr VirtualRobot::Robot::clone ( CollisionCheckerPtr  collisionChecker = CollisionCheckerPtr(),
float  scaling = 1.0f,
bool  preventCloningMeshesIfScalingIs1 = false 
)
virtual

◆ cloneScaling()

RobotPtr VirtualRobot::Robot::cloneScaling ( )
virtual

Clones this robot and keeps the current scaling for the robot and each robot node.

◆ createVisualizationFromCollisionModels()

void VirtualRobot::Robot::createVisualizationFromCollisionModels ( )
protected

Goes through all RobotNodes and if no visualization is present: the collision model is checked and in case it owns a visualization it is cloned and used as visualization.

◆ deregisterRobotNode()

virtual void VirtualRobot::Robot::deregisterRobotNode ( RobotNodePtr  node)
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ deregisterRobotNodeSet()

virtual void VirtualRobot::Robot::deregisterRobotNodeSet ( RobotNodeSetPtr  nodeSet)
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ extractSubPart()

VirtualRobot::RobotPtr VirtualRobot::Robot::extractSubPart ( RobotNodePtr  startJoint,
const std::string &  newRobotType,
const std::string &  newRobotName,
bool  cloneRNS = true,
bool  cloneEEFs = true,
CollisionCheckerPtr  collisionChecker = CollisionCheckerPtr(),
float  scaling = 1.0f,
bool  preventCloningMeshesIfScalingIs1 = false 
)
virtual

Extract a sub kinematic from this robot and create a new robot instance.

Parameters
startJointThe kinematic starts with this RobotNode
newRobotTypeThe name of the newly created robot type
newRobotNameThe name of the newly created robot
cloneRNSClone all robot node sets that belong to the original robot and for which the remaining robot nodes of the subPart are sufficient.
cloneEEFsClone all end effectors that belong to the original robot and for which the remaining robot nodes of the subPart are sufficient.
collisionCheckerThe new robot can be registered to a different collision checker. If not set, the collision checker of the original robot is used.
scalingCan be set to create a scaled version of this robot. Scaling is applied on kinematic, visual, and collision data.

◆ getBoundingBox()

VirtualRobot::BoundingBox VirtualRobot::Robot::getBoundingBox ( bool  collisionModel = true) const
virtual

The (current) bounding box in global coordinate system.

Parameters
collisionModelEither the collision or the visualization model is considered.
Returns
The bounding box.

◆ getCollisionChecker()

VirtualRobot::CollisionCheckerPtr VirtualRobot::Robot::getCollisionChecker ( )
overridevirtual

Reimplemented from VirtualRobot::SceneObject.

◆ getCollisionModels()

std::vector< CollisionModelPtr > VirtualRobot::Robot::getCollisionModels ( ) const
virtual

◆ getCoMGlobal()

Eigen::Vector3f VirtualRobot::Robot::getCoMGlobal ( )
overridevirtual

Return Center of Mass of this robot in global coordinates. All RobotNodes of this robot are considered according to their mass.

Reimplemented from VirtualRobot::SceneObject.

◆ getCoMLocal()

Eigen::Vector3f VirtualRobot::Robot::getCoMLocal ( )
overridevirtual

Return center of mass of this robot in local coordinate frame. All RobotNodes of this robot are considered according to their mass.

Reimplemented from VirtualRobot::SceneObject.

◆ getConfig()

VirtualRobot::RobotConfigPtr VirtualRobot::Robot::getConfig ( ) const
virtual

get the complete setup of all robot nodes

◆ getEndEffector()

virtual EndEffectorPtr VirtualRobot::Robot::getEndEffector ( const std::string &  endEffectorName) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ getEndEffectors() [1/2]

std::vector< EndEffectorPtr > VirtualRobot::Robot::getEndEffectors ( ) const
virtual

◆ getEndEffectors() [2/2]

virtual void VirtualRobot::Robot::getEndEffectors ( std::vector< EndEffectorPtr > &  storeEEF) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ getFilename()

std::string VirtualRobot::Robot::getFilename ( ) const
virtual

Retrieve the stored filename.

◆ getGlobalPoseForRobotNode()

Eigen::Matrix4f VirtualRobot::Robot::getGlobalPoseForRobotNode ( const RobotNodePtr node,
const Eigen::Matrix4f &  globalPoseNode 
) const
virtual

Get the global pose of this robot so that the RobotNode node is at pose globalPoseNode.

◆ getGlobalPositionForRobotNode()

Eigen::Matrix4f VirtualRobot::Robot::getGlobalPositionForRobotNode ( const RobotNodePtr node,
const Eigen::Vector3f &  globalPositionNode 
) const
virtual

Get the global position of this robot so that the RobotNode node is at position globalPoseNode.

◆ getJointValues()

std::map< std::string, float > VirtualRobot::Robot::getJointValues ( ) const
virtual

◆ getMass()

float VirtualRobot::Robot::getMass ( ) const
virtual

Return accumulated mass of this robot.

◆ getName()

std::string VirtualRobot::Robot::getName ( ) const
virtual

◆ getNodeMapping()

const NodeMapping & VirtualRobot::Robot::getNodeMapping ( ) const

Node mapping

◆ getNumFaces()

int VirtualRobot::Robot::getNumFaces ( bool  collisionModel = false)
overridevirtual

get number of faces (i.e. triangles) of this object collisionModel Indicates weather the faces of the collision model or the full model should be returned.

Reimplemented from VirtualRobot::SceneObject.

◆ getPropagatingJointValuesEnabled()

bool VirtualRobot::Robot::getPropagatingJointValuesEnabled ( ) const

◆ getReadLock()

ReadLockPtr VirtualRobot::Robot::getReadLock ( )
virtual

This readlock can be used to protect data access. It locks the mutex until deletion. For internal use. API users will usually not need this functionality since all data access is protected automatically.

Exemplary usage: { ReadLockPtr lock = robot->getReadLock(); now the mutex is locked

access data ...

        } // end of scope -> lock gets deleted and mutex is released automatically

◆ getRobotNode()

virtual RobotNodePtr VirtualRobot::Robot::getRobotNode ( const std::string &  robotNodeName) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ getRobotNodeNames()

std::vector< std::string > VirtualRobot::Robot::getRobotNodeNames ( ) const
virtual

◆ getRobotNodes() [1/2]

std::vector< RobotNodePtr > VirtualRobot::Robot::getRobotNodes ( ) const
virtual

◆ getRobotNodes() [2/2]

virtual void VirtualRobot::Robot::getRobotNodes ( std::vector< RobotNodePtr > &  storeNodes,
bool  clearVector = true 
) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ getRobotNodeSet()

virtual RobotNodeSetPtr VirtualRobot::Robot::getRobotNodeSet ( const std::string &  nodeSetName) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ getRobotNodeSetNames()

std::vector< std::string > VirtualRobot::Robot::getRobotNodeSetNames ( ) const
virtual

◆ getRobotNodeSets() [1/2]

std::vector< RobotNodeSetPtr > VirtualRobot::Robot::getRobotNodeSets ( ) const
virtual

◆ getRobotNodeSets() [2/2]

virtual void VirtualRobot::Robot::getRobotNodeSets ( std::vector< RobotNodeSetPtr > &  storeNodeSet) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ getRootNode()

virtual RobotNodePtr VirtualRobot::Robot::getRootNode ( ) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ getScaling()

float VirtualRobot::Robot::getScaling ( ) const

◆ getSensor() [1/2]

SensorPtr VirtualRobot::Robot::getSensor ( const std::string &  name) const
virtual

Returns the sensor with the given name.

◆ getSensor() [2/2]

template<class SensorType >
std::shared_ptr<SensorType> VirtualRobot::Robot::getSensor ( const std::string &  name) const
inline

◆ getSensors() [1/2]

std::vector< SensorPtr > VirtualRobot::Robot::getSensors ( ) const
virtual

Returns all sensors that are defined within this robot.

◆ getSensors() [2/2]

template<class SensorType >
std::vector<std::shared_ptr<SensorType> > VirtualRobot::Robot::getSensors ( ) const
inline

◆ getType()

std::string VirtualRobot::Robot::getType ( ) const
virtual

◆ getVisualization()

template<typename T >
std::shared_ptr< T > VirtualRobot::Robot::getVisualization ( SceneObject::VisualizationType  visuType = SceneObject::Full,
bool  sensors = true 
)

Retrieve a visualization in the given format.

Parameters
visuTypeThe visualization type (Full or Collision model)
sensorsAdd sensors models to the visualization. Example usage: std::shared_ptr<VirtualRobot::CoinVisualization> visualization = robot->getVisualization<CoinVisualization>(); SoNode* visualisationNode = NULL; if (visualization) visualisationNode = visualization->getCoinVisualization();

This method collects all visualization nodes and creates a new Visualization subclass which is given by the template parameter T. T must be a subclass of VirtualRobot::Visualization. A compile time error is thrown if a different class type is used as template argument.

◆ getWriteLock()

WriteLockPtr VirtualRobot::Robot::getWriteLock ( )
virtual

This writelock can be used to protect data access. It locks the mutex until deletion. For internal use. API users will usually not need this functionality since all data access is protected automatically.

Exemplary usage: { WriteLockPtr lock = robot->getWriteLock(); now the mutex is locked

access data ...

        } // end of scope -> lock gets deleted and mutex is released automatically

◆ hasEndEffector() [1/2]

bool VirtualRobot::Robot::hasEndEffector ( EndEffectorPtr  endEffector) const
virtual
Returns
true if instance of VirtualRobot::Robot contains a reference to endEffector and false otherwise

◆ hasEndEffector() [2/2]

virtual bool VirtualRobot::Robot::hasEndEffector ( const std::string &  endEffectorName) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ hasRobotNode() [1/2]

virtual bool VirtualRobot::Robot::hasRobotNode ( RobotNodePtr  node) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ hasRobotNode() [2/2]

virtual bool VirtualRobot::Robot::hasRobotNode ( const std::string &  robotNodeName) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ hasRobotNodeSet() [1/2]

bool VirtualRobot::Robot::hasRobotNodeSet ( RobotNodeSetPtr  nodeSet) const
virtual

◆ hasRobotNodeSet() [2/2]

virtual bool VirtualRobot::Robot::hasRobotNodeSet ( const std::string &  name) const
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ highlight()

void VirtualRobot::Robot::highlight ( VisualizationPtr  visualization,
bool  enable 
)
virtual

Convenient method for highlighting the visualization of this robot. It is automatically checked whether the collision model or the full model is part of the visualization.

Parameters
visualizationThe visualization for which the highlighting should be performed.
enableOn or off

◆ inflateCollisionModel()

void VirtualRobot::Robot::inflateCollisionModel ( float  inflationInMM)

Inflates the collision models of all robot nodes of this robot. Useful for motion planning with a safety margin.

Parameters
inflationInMMThe collision model is inflated by this value. This value is absolute to the original collision model. Repetitive inflation with the same value has no effect.

◆ isPassive()

bool VirtualRobot::Robot::isPassive ( ) const
inline

◆ print()

void VirtualRobot::Robot::print ( bool  printChildren = false,
bool  printDecoration = true 
) const
overridevirtual

Print status information.

Reimplemented from VirtualRobot::SceneObject.

◆ registerEndEffector()

virtual void VirtualRobot::Robot::registerEndEffector ( EndEffectorPtr  endEffector)
pure virtual

Implemented in VirtualRobot::LocalRobot.

◆ registerNodeMapping()

void VirtualRobot::Robot::registerNodeMapping ( const NodeMapping nodeMapping)

◆ registerRobotNode()

virtual void VirtualRobot::Robot::registerRobotNode ( RobotNodePtr  node)
pure virtual

This method is automatically called in RobotNode's initialization routine.

Implemented in VirtualRobot::LocalRobot.

◆ registerRobotNodeSet()

virtual void VirtualRobot::Robot::registerRobotNodeSet ( RobotNodeSetPtr  nodeSet)
pure virtual

This method is automatically called in RobotNodeSet's initialization routine.

Implemented in VirtualRobot::LocalRobot.

◆ setConfig()

bool VirtualRobot::Robot::setConfig ( RobotConfigPtr  c)
virtual

Sets the configuration according to the RobotNodes, defined in c. All other nodes are not affected.

◆ setFilename()

void VirtualRobot::Robot::setFilename ( const std::string &  filename)
virtual

Just storing the filename.

◆ setGlobalPose() [1/2]

virtual void VirtualRobot::Robot::setGlobalPose ( const Eigen::Matrix4f &  globalPose,
bool  applyValues 
)
pure virtual

Set the global pose of this robot.

Implemented in VirtualRobot::LocalRobot.

◆ setGlobalPose() [2/2]

void VirtualRobot::Robot::setGlobalPose ( const Eigen::Matrix4f &  pose)
overridevirtual

Update the pose of this object. The visualization and collision models are updated accordingly.

Parameters
poseThe new pose of this object

Reimplemented from VirtualRobot::SceneObject.

Reimplemented in VirtualRobot::LocalRobot.

◆ setGlobalPoseForRobotNode()

void VirtualRobot::Robot::setGlobalPoseForRobotNode ( const RobotNodePtr node,
const Eigen::Matrix4f &  globalPoseNode 
)
virtual

Set the global pose of this robot so that the RobotNode node is at pose globalPoseNode.

◆ setGlobalPositionForRobotNode()

void VirtualRobot::Robot::setGlobalPositionForRobotNode ( const RobotNodePtr node,
const Eigen::Vector3f &  globalPositionNode 
)
virtual

Set the global position of this robot so that the RobotNode node is at position globalPoseNode.

◆ setJointValue() [1/2]

void VirtualRobot::Robot::setJointValue ( RobotNodePtr  rn,
float  jointValue 
)
virtual

Set a joint value [rad]. The internal matrices and visualizations are updated accordingly. If you intend to update multiple joints, use setJointValues for faster access.

◆ setJointValue() [2/2]

void VirtualRobot::Robot::setJointValue ( const std::string &  nodeName,
float  jointValue 
)
virtual

Set a joint value [rad]. The internal matrices and visualizations are updated accordingly. If you intend to update multiple joints, use setJointValues for faster access.

◆ setJointValues() [1/8]

void VirtualRobot::Robot::setJointValues ( const std::map< std::string, float > &  jointValues)
virtual

Set joint values [rad]. The complete robot is updated to apply the new joint values.

Parameters
jointValuesA map containing RobotNode names with according values.

◆ setJointValues() [2/8]

void VirtualRobot::Robot::setJointValues ( const std::map< RobotNodePtr, float > &  jointValues)
virtual

Set joint values [rad]. The complete robot is updated to apply the new joint values.

Parameters
jointValuesA map containing RobotNodes with according values.

◆ setJointValues() [3/8]

void VirtualRobot::Robot::setJointValues ( RobotNodeSetPtr  rns,
const std::vector< float > &  jointValues 
)
virtual

Set joint values [rad]. The subpart of the robot, defined by the start joint (kinematicRoot) of rns, is updated to apply the new joint values.

Parameters
rnsThe RobotNodeSet defines the joints
jointValuesA vector with joint values, size must be equal to rns.

◆ setJointValues() [4/8]

void VirtualRobot::Robot::setJointValues ( const std::vector< RobotNodePtr rn,
const std::vector< float > &  jointValues 
)
virtual

Set joint values [rad]. The complete robot is updated to apply the new joint values.

Parameters
rnThe RobotNodes
jointValuesA vector with joint values, size must be equal to rn.

◆ setJointValues() [5/8]

void VirtualRobot::Robot::setJointValues ( RobotNodeSetPtr  rns,
const Eigen::VectorXf &  jointValues 
)
virtual

Set joint values [rad]. The subpart of the robot, defined by the start joint (kinematicRoot) of rns, is updated to apply the new joint values.

Parameters
rnsThe RobotNodeSet defines the joints
jointValuesA vector with joint values, size must be equal to rns.

◆ setJointValues() [6/8]

void VirtualRobot::Robot::setJointValues ( RobotConfigPtr  config)
virtual

Set joint values [rad]. The complete robot is updated to apply the new joint values.

Parameters
configThe RobotConfig defines the RobotNodes and joint values.

◆ setJointValues() [7/8]

void VirtualRobot::Robot::setJointValues ( RobotNodeSetPtr  rns,
RobotConfigPtr  config 
)
virtual

Set joint values [rad]. Only those joints in config are affected which are present in rns. The subpart of the robot, defined by the start joint (kinematicRoot) of rns, is updated to apply the new joint values.

Parameters
rnsOnly joints in this rns are updated.
configThe RobotConfig defines the RobotNodes and joint values.

◆ setJointValues() [8/8]

void VirtualRobot::Robot::setJointValues ( TrajectoryPtr  trajectory,
float  t 
)
virtual

Apply configuration of trajectory at time t

Parameters
trajectoryThe trajectory
tThe time (0<=t<=1)

◆ setName()

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

◆ setPassive()

void VirtualRobot::Robot::setPassive ( )
inline

◆ setPropagatingJointValuesEnabled()

void VirtualRobot::Robot::setPropagatingJointValuesEnabled ( bool  enabled)

◆ setRootNode()

virtual void VirtualRobot::Robot::setRootNode ( RobotNodePtr  node)
pure virtual

The root node is the first RobotNode of this robot.

Implemented in VirtualRobot::LocalRobot.

◆ setScaling()

void VirtualRobot::Robot::setScaling ( float  scaling)

◆ setThreadsafe()

void VirtualRobot::Robot::setThreadsafe ( bool  flag)
virtual

Configures the robot to threadsafe or not. Per default the robot is threadsafe, i.e., updating the robot state and reading the Poses from the nodes is mutual exclusive. This feature can be turned off, however, in order to be make data access faster in single threaded applications.

◆ setType()

void VirtualRobot::Robot::setType ( const std::string &  type)

◆ setUpdateCollisionModel()

void VirtualRobot::Robot::setUpdateCollisionModel ( bool  enable)
overridevirtual

Reimplemented from VirtualRobot::SceneObject.

◆ setUpdateVisualization()

void VirtualRobot::Robot::setUpdateVisualization ( bool  enable)
overridevirtual

Enables/Disables the visualization updates of collision model and visualization model.

Reimplemented from VirtualRobot::SceneObject.

◆ setupVisualization()

void VirtualRobot::Robot::setupVisualization ( bool  showVisualization,
bool  showAttachedVisualizations 
)
overridevirtual

Setup the full model visualization.

Parameters
showVisualizationIf false, the visualization is disabled.
showAttachedVisualizationsIf false, the visualization of any attached optional visualizations is disabled.

Reimplemented from VirtualRobot::SceneObject.

◆ shared_from_this()

std::shared_ptr< Robot > VirtualRobot::Robot::shared_from_this ( ) const

◆ showCoordinateSystems()

void VirtualRobot::Robot::showCoordinateSystems ( bool  enable,
const std::string &  type = "" 
)

Shows the coordinate systems of the robot nodes

◆ showPhysicsInformation()

void VirtualRobot::Robot::showPhysicsInformation ( bool  enableCoM,
bool  enableInertial,
VisualizationNodePtr  comModel = VisualizationNodePtr() 
)
overridevirtual

Display some physics debugging information. enableCoM If true, the center of mass is shown (if given). If a comModel is given it is used for visualization, otherwise a standrad marker is shown. enableInertial If true, a visualization of the inertial matrix is shown (if given). comModel If set, this visualization is used to display the CoM location. If not set, a standard marker is used.

Reimplemented from VirtualRobot::SceneObject.

◆ showStructure()

void VirtualRobot::Robot::showStructure ( bool  enable,
const std::string &  type = "" 
)

Shows the structure of the robot

◆ toXML()

std::string VirtualRobot::Robot::toXML ( const std::string &  basePath = ".",
const std::string &  modelPath = "models",
bool  storeEEF = true,
bool  storeRNS = true,
bool  storeSensors = true,
bool  storeModelFiles = true 
) const
virtual

Creates an XML string that defines the complete robot. Filenames of all visualization models are set to modelPath/RobotNodeName_visu and/or modelPath/RobotNodeName_colmodel.

See also
RobotIO::saveXML.

◆ validateNodeMapping()

void VirtualRobot::Robot::validateNodeMapping ( const NodeMapping nodeMapping) const
protected

Friends And Related Function Documentation

◆ RobotIO

friend class RobotIO
friend

Field Documentation

◆ filename

std::string VirtualRobot::Robot::filename
protected

◆ mutex

std::recursive_mutex VirtualRobot::Robot::mutex
mutableprotected

◆ NullPtr

const RobotPtr VirtualRobot::Robot::NullPtr {nullptr}
static

◆ passive

bool VirtualRobot::Robot::passive {false}
protected

◆ propagatingJointValuesEnabled

bool VirtualRobot::Robot::propagatingJointValuesEnabled = true
protected

◆ type

std::string VirtualRobot::Robot::type
protected

◆ updateVisualization

bool VirtualRobot::Robot::updateVisualization
protected

◆ use_mutex

bool VirtualRobot::Robot::use_mutex
protected