Classes | Public Member Functions | Private Member Functions | Private Attributes
srdf::Model Class Reference

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

#include <model.h>

List of all members.

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.
const std::vector
< DisabledCollision > & 
getDisabledCollisionPairs () const
 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)
const std::vector< EndEffector > & getEndEffectors () const
 Get the list of end effectors defined for this model.
__attribute__((deprecated))
std const std::vector< Group > & 
getGroups () const
 Get the list of groups defined for this model.
const std::vector< GroupState > & getGroupStates () const
 Get the list of group states defined for this model.
const std::vector< LinkSpheres > & getLinkSphereApproximations () const
 Get the collision spheres list.
const std::string & getName () const
 Get the name of this model.
const std::vector< PassiveJoint > & getPassiveJoints () const
 Get the list of known passive joints.
const std::vector< VirtualJoint > & getVirtualJoints () const
 Get the list of virtual joints defined for this model.
bool initFile (const urdf::ModelInterface &urdf_model, const std::string &filename)
 Load Model given a filename.
bool initString (const urdf::ModelInterface &urdf_model, const std::string &xmlstring)
 Load Model from a XML-string.
bool initXml (const urdf::ModelInterface &urdf_model, TiXmlElement *xml)
 Load Model from TiXMLElement.
bool initXml (const urdf::ModelInterface &urdf_model, TiXmlDocument *xml)
 Load Model from TiXMLDocument.
 Model ()
 ~Model ()

Private Member Functions

void loadDisabledCollisions (const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
void loadEndEffectors (const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
void loadGroups (const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
void loadGroupStates (const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
void loadLinkSphereApproximations (const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
void loadPassiveJoints (const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
void loadVirtualJoints (const urdf::ModelInterface &urdf_model, TiXmlElement *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 58 of file model.h.


Constructor & Destructor Documentation

srdf::Model::Model ( ) [inline]

Definition at line 62 of file model.h.

srdf::Model::~Model ( ) [inline]

Definition at line 66 of file model.h.


Member Function Documentation

Clear the model.

Definition at line 627 of file model.cpp.

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 211 of file model.h.

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

Get the list of end effectors defined for this model.

Definition at line 233 of file model.h.

__attribute__ ((deprecated)) std const std::vector<Group>& srdf::Model::getGroups ( ) const [inline]

Get the list of groups defined for this model.

Deprecated:
{ Use the version returning DisabledCollision }

Definition at line 221 of file model.h.

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

Get the list of group states defined for this model.

Definition at line 239 of file model.h.

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

Get the collision spheres list.

Definition at line 251 of file model.h.

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

Get the name of this model.

Definition at line 205 of file model.h.

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

Get the list of known passive joints.

Definition at line 245 of file model.h.

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

Get the list of virtual joints defined for this model.

Definition at line 227 of file model.h.

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

Load Model given a filename.

Definition at line 596 of file model.cpp.

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

Load Model from a XML-string.

Definition at line 619 of file model.cpp.

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

Load Model from TiXMLElement.

Definition at line 553 of file model.cpp.

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

Load Model from TiXMLDocument.

Definition at line 584 of file model.cpp.

void srdf::Model::loadDisabledCollisions ( const urdf::ModelInterface &  urdf_model,
TiXmlElement *  robot_xml 
) [private]

Definition at line 494 of file model.cpp.

void srdf::Model::loadEndEffectors ( const urdf::ModelInterface &  urdf_model,
TiXmlElement *  robot_xml 
) [private]

Definition at line 355 of file model.cpp.

void srdf::Model::loadGroups ( const urdf::ModelInterface &  urdf_model,
TiXmlElement *  robot_xml 
) [private]

Definition at line 95 of file model.cpp.

void srdf::Model::loadGroupStates ( const urdf::ModelInterface &  urdf_model,
TiXmlElement *  robot_xml 
) [private]

Definition at line 268 of file model.cpp.

void srdf::Model::loadLinkSphereApproximations ( const urdf::ModelInterface &  urdf_model,
TiXmlElement *  robot_xml 
) [private]

Definition at line 407 of file model.cpp.

void srdf::Model::loadPassiveJoints ( const urdf::ModelInterface &  urdf_model,
TiXmlElement *  robot_xml 
) [private]

Definition at line 525 of file model.cpp.

void srdf::Model::loadVirtualJoints ( const urdf::ModelInterface &  urdf_model,
TiXmlElement *  robot_xml 
) [private]

Definition at line 47 of file model.cpp.


Member Data Documentation

Definition at line 275 of file model.h.

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

Definition at line 273 of file model.h.

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

Definition at line 271 of file model.h.

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

Definition at line 270 of file model.h.

Definition at line 274 of file model.h.

std::string srdf::Model::name_ [private]

Definition at line 269 of file model.h.

Definition at line 276 of file model.h.

Definition at line 272 of file model.h.


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


srdfdom
Author(s): Ioan Sucan , Guillaume Walck
autogenerated on Thu Feb 9 2017 03:50:57