Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
srdf::Model Class Reference

Representation of semantic information about the robot. More...

#include <model.h>

Classes

struct  DisabledCollision
 The definition of a disabled collision between two links. More...
 
struct  EndEffector
 Representation of an end effector. More...
 
struct  Group
 A group consists of a set of joints and the corresponding descendant links. There are multiple ways to specify a group. Directly specifying joints, links or chains, or referring to other defined groups. More...
 
struct  GroupState
 A named state for a particular group. More...
 
struct  LinkSpheres
 The definition of a list of spheres for a link. More...
 
struct  PassiveJoint
 
struct  Sphere
 The definition of a sphere. More...
 
struct  VirtualJoint
 

Public Member Functions

void clear ()
 Clear the model. More...
 
const std::vector< DisabledCollision > & getDisabledCollisionPairs () const
 
std::vector< std::pair< std::string, std::string > > getDisabledCollisions () const
 
const std::vector< EndEffector > & getEndEffectors () const
 Get the list of end effectors defined for this model. More...
 
const std::vector< Group > & getGroups () const
 Get the list of groups defined for this model. More...
 
const std::vector< GroupState > & getGroupStates () const
 Get the list of group states defined for this model. More...
 
const std::vector< LinkSpheres > & getLinkSphereApproximations () const
 Get the collision spheres list. More...
 
const std::string & getName () const
 Get the name of this model. More...
 
const std::vector< PassiveJoint > & getPassiveJoints () const
 Get the list of known passive joints. More...
 
const std::vector< VirtualJoint > & getVirtualJoints () const
 Get the list of virtual joints defined for this model. More...
 
bool initFile (const urdf::ModelInterface &urdf_model, const std::string &filename)
 Load Model given a filename. More...
 
bool initString (const urdf::ModelInterface &urdf_model, const std::string &xmlstring)
 Load Model from a XML-string. More...
 
bool initXml (const urdf::ModelInterface &urdf_model, tinyxml2::XMLDocument *xml)
 Load Model from XMLDocument. More...
 
bool initXml (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *xml)
 Load Model from XMLElement. More...
 
 Model ()
 
 ~Model ()
 

Private Member Functions

void loadDisabledCollisions (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
 
void loadEndEffectors (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
 
void loadGroups (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
 
void loadGroupStates (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
 
void loadLinkSphereApproximations (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
 
void loadPassiveJoints (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
 
void loadVirtualJoints (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
 

Private Attributes

std::vector< DisabledCollisiondisabled_collisions_
 
std::vector< EndEffectorend_effectors_
 
std::vector< GroupStategroup_states_
 
std::vector< Groupgroups_
 
std::vector< LinkSphereslink_sphere_approximations_
 
std::string name_
 
std::vector< PassiveJointpassive_joints_
 
std::vector< VirtualJointvirtual_joints_
 

Detailed Description

Representation of semantic information about the robot.

Definition at line 84 of file model.h.

Constructor & Destructor Documentation

◆ Model()

srdf::Model::Model ( )
inline

Definition at line 119 of file model.h.

◆ ~Model()

srdf::Model::~Model ( )
inline

Definition at line 123 of file model.h.

Member Function Documentation

◆ clear()

void srdf::Model::clear ( )

Clear the model.

Definition at line 668 of file model.cpp.

◆ getDisabledCollisionPairs()

const std::vector<DisabledCollision>& srdf::Model::getDisabledCollisionPairs ( ) const
inline

Get the list of pairs of links that need not be checked for collisions (because they can never touch given the geometry and kinematics of the robot)

Definition at line 270 of file model.h.

◆ getDisabledCollisions()

std::vector< std::pair< std::string, std::string > > srdf::Model::getDisabledCollisions ( ) const
Deprecated:

Definition at line 680 of file model.cpp.

◆ getEndEffectors()

const std::vector<EndEffector>& srdf::Model::getEndEffectors ( ) const
inline

Get the list of end effectors defined for this model.

Definition at line 291 of file model.h.

◆ getGroups()

const std::vector<Group>& srdf::Model::getGroups ( ) const
inline

Get the list of groups defined for this model.

Definition at line 279 of file model.h.

◆ getGroupStates()

const std::vector<GroupState>& srdf::Model::getGroupStates ( ) const
inline

Get the list of group states defined for this model.

Definition at line 297 of file model.h.

◆ getLinkSphereApproximations()

const std::vector<LinkSpheres>& srdf::Model::getLinkSphereApproximations ( ) const
inline

Get the collision spheres list.

Definition at line 309 of file model.h.

◆ getName()

const std::string& srdf::Model::getName ( ) const
inline

Get the name of this model.

Definition at line 263 of file model.h.

◆ getPassiveJoints()

const std::vector<PassiveJoint>& srdf::Model::getPassiveJoints ( ) const
inline

Get the list of known passive joints.

Definition at line 303 of file model.h.

◆ getVirtualJoints()

const std::vector<VirtualJoint>& srdf::Model::getVirtualJoints ( ) const
inline

Get the list of virtual joints defined for this model.

Definition at line 285 of file model.h.

◆ initFile()

bool srdf::Model::initFile ( const urdf::ModelInterface &  urdf_model,
const std::string &  filename 
)

Load Model given a filename.

Definition at line 634 of file model.cpp.

◆ initString()

bool srdf::Model::initString ( const urdf::ModelInterface &  urdf_model,
const std::string &  xmlstring 
)

Load Model from a XML-string.

Definition at line 657 of file model.cpp.

◆ initXml() [1/2]

bool srdf::Model::initXml ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLDocument *  xml 
)

Load Model from XMLDocument.

◆ initXml() [2/2]

bool srdf::Model::initXml ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  xml 
)

Load Model from XMLElement.

◆ loadDisabledCollisions()

void srdf::Model::loadDisabledCollisions ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  robot_xml 
)
private

Definition at line 535 of file model.cpp.

◆ loadEndEffectors()

void srdf::Model::loadEndEffectors ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  robot_xml 
)
private

Definition at line 380 of file model.cpp.

◆ loadGroups()

void srdf::Model::loadGroups ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  robot_xml 
)
private

Definition at line 103 of file model.cpp.

◆ loadGroupStates()

void srdf::Model::loadGroupStates ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  robot_xml 
)
private

Definition at line 284 of file model.cpp.

◆ loadLinkSphereApproximations()

void srdf::Model::loadLinkSphereApproximations ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  robot_xml 
)
private

Definition at line 438 of file model.cpp.

◆ loadPassiveJoints()

void srdf::Model::loadPassiveJoints ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  robot_xml 
)
private

Definition at line 567 of file model.cpp.

◆ loadVirtualJoints()

void srdf::Model::loadVirtualJoints ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  robot_xml 
)
private

Definition at line 48 of file model.cpp.

Member Data Documentation

◆ disabled_collisions_

std::vector<DisabledCollision> srdf::Model::disabled_collisions_
private

Definition at line 332 of file model.h.

◆ end_effectors_

std::vector<EndEffector> srdf::Model::end_effectors_
private

Definition at line 330 of file model.h.

◆ group_states_

std::vector<GroupState> srdf::Model::group_states_
private

Definition at line 328 of file model.h.

◆ groups_

std::vector<Group> srdf::Model::groups_
private

Definition at line 327 of file model.h.

◆ link_sphere_approximations_

std::vector<LinkSpheres> srdf::Model::link_sphere_approximations_
private

Definition at line 331 of file model.h.

◆ name_

std::string srdf::Model::name_
private

Definition at line 326 of file model.h.

◆ passive_joints_

std::vector<PassiveJoint> srdf::Model::passive_joints_
private

Definition at line 333 of file model.h.

◆ virtual_joints_

std::vector<VirtualJoint> srdf::Model::virtual_joints_
private

Definition at line 329 of file model.h.


The documentation for this class was generated from the following files:


srdfdom
Author(s): Ioan Sucan , Guillaume Walck
autogenerated on Tue Jun 22 2021 07:34:51