Classes | Public Types | 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  CollisionPair
 The definition of a disabled/enabled 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 Types

using JointPropertyMap = std::map< std::string, PropertyMap >
 
using PropertyMap = std::map< std::string, std::string >
 

Public Member Functions

void clear ()
 Clear the model. More...
 
const std::vector< CollisionPair > & getDisabledCollisionPairs () const
 Get the list of pairs of links for which we explicitly disable collision. More...
 
const std::vector< CollisionPair > & getEnabledCollisionPairs () const
 Get the list of pairs of links for which we explicitly re-enable collision (after having disabled it via a default) More...
 
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 JointPropertyMapgetJointProperties () const
 Get the joint properties map. More...
 
const PropertyMapgetJointProperties (const std::string &joint_name) const
 Get the joint properties for a particular joint. 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< std::string > & getNoDefaultCollisionLinks () const
 Get the list of links that should have collision checking disabled by default (and only selectively enabled) 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

bool isValidJoint (const urdf::ModelInterface &urdf_model, const std::string &name) const
 
void loadCollisionDefaults (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
 
void loadCollisionPairs (const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml, const char *tag_name, std::vector< CollisionPair > &pairs)
 
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 loadJointProperties (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< CollisionPairdisabled_collision_pairs_
 
std::vector< CollisionPairenabled_collision_pairs_
 
std::vector< EndEffectorend_effectors_
 
std::vector< GroupStategroup_states_
 
std::vector< Groupgroups_
 
JointPropertyMap joint_properties_
 
std::vector< LinkSphereslink_sphere_approximations_
 
std::string name_
 
std::vector< std::string > no_default_collision_links_
 
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.

Member Typedef Documentation

◆ JointPropertyMap

using srdf::Model::JointPropertyMap = std::map<std::string, PropertyMap>

Definition at line 120 of file model.h.

◆ PropertyMap

using srdf::Model::PropertyMap = std::map<std::string, std::string>

Definition at line 119 of file model.h.

Constructor & Destructor Documentation

◆ Model()

srdf::Model::Model ( )
inline

Definition at line 122 of file model.h.

◆ ~Model()

srdf::Model::~Model ( )
inline

Definition at line 126 of file model.h.

Member Function Documentation

◆ clear()

void srdf::Model::clear ( )

Clear the model.

Definition at line 717 of file model.cpp.

◆ getDisabledCollisionPairs()

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

Get the list of pairs of links for which we explicitly disable collision.

Definition at line 284 of file model.h.

◆ getEnabledCollisionPairs()

const std::vector<CollisionPair>& srdf::Model::getEnabledCollisionPairs ( ) const
inline

Get the list of pairs of links for which we explicitly re-enable collision (after having disabled it via a default)

Definition at line 278 of file model.h.

◆ getEndEffectors()

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

Get the list of end effectors defined for this model.

Definition at line 302 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 290 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 308 of file model.h.

◆ getJointProperties() [1/2]

const JointPropertyMap& srdf::Model::getJointProperties ( ) const
inline

Get the joint properties map.

Definition at line 338 of file model.h.

◆ getJointProperties() [2/2]

const PropertyMap& srdf::Model::getJointProperties ( const std::string &  joint_name) const
inline

Get the joint properties for a particular joint.

Definition at line 326 of file model.h.

◆ getLinkSphereApproximations()

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

Get the collision spheres list.

Definition at line 320 of file model.h.

◆ getName()

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

Get the name of this model.

Definition at line 266 of file model.h.

◆ getNoDefaultCollisionLinks()

const std::vector<std::string>& srdf::Model::getNoDefaultCollisionLinks ( ) const
inline

Get the list of links that should have collision checking disabled by default (and only selectively enabled)

Definition at line 272 of file model.h.

◆ getPassiveJoints()

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

Get the list of known passive joints.

Definition at line 314 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 296 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 683 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 706 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.

◆ isValidJoint()

bool srdf::Model::isValidJoint ( const urdf::ModelInterface &  urdf_model,
const std::string &  name 
) const
private

Definition at line 48 of file model.cpp.

◆ loadCollisionDefaults()

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

Definition at line 531 of file model.cpp.

◆ loadCollisionPairs()

void srdf::Model::loadCollisionPairs ( const urdf::ModelInterface &  urdf_model,
tinyxml2::XMLElement *  robot_xml,
const char *  tag_name,
std::vector< CollisionPair > &  pairs 
)
private

Definition at line 552 of file model.cpp.

◆ loadEndEffectors()

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

Definition at line 376 of file model.cpp.

◆ loadGroups()

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

Definition at line 119 of file model.cpp.

◆ loadGroupStates()

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

Definition at line 290 of file model.cpp.

◆ loadJointProperties()

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

Definition at line 605 of file model.cpp.

◆ loadLinkSphereApproximations()

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

Definition at line 434 of file model.cpp.

◆ loadPassiveJoints()

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

Definition at line 582 of file model.cpp.

◆ loadVirtualJoints()

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

Definition at line 64 of file model.cpp.

Member Data Documentation

◆ disabled_collision_pairs_

std::vector<CollisionPair> srdf::Model::disabled_collision_pairs_
private

Definition at line 368 of file model.h.

◆ enabled_collision_pairs_

std::vector<CollisionPair> srdf::Model::enabled_collision_pairs_
private

Definition at line 367 of file model.h.

◆ end_effectors_

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

Definition at line 364 of file model.h.

◆ group_states_

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

Definition at line 362 of file model.h.

◆ groups_

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

Definition at line 361 of file model.h.

◆ joint_properties_

JointPropertyMap srdf::Model::joint_properties_
private

Definition at line 370 of file model.h.

◆ link_sphere_approximations_

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

Definition at line 365 of file model.h.

◆ name_

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

Definition at line 360 of file model.h.

◆ no_default_collision_links_

std::vector<std::string> srdf::Model::no_default_collision_links_
private

Definition at line 366 of file model.h.

◆ passive_joints_

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

Definition at line 369 of file model.h.

◆ virtual_joints_

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

Definition at line 363 of file model.h.


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


srdfdom
Author(s): Ioan Sucan , Guillaume Walck
autogenerated on Fri Jul 7 2023 02:22:48