Class Model
Defined in File model.h
Nested Relationships
Nested Types
Class Documentation
-
class Model
Representation of semantic information about the robot.
Public Functions
-
inline Model()
-
inline ~Model()
-
bool initXml(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *xml)
Load Model from XMLElement.
-
bool initXml(const urdf::ModelInterface &urdf_model, tinyxml2::XMLDocument *xml)
Load Model from XMLDocument.
-
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.
-
inline const std::string &getName() const
Get the name of this model.
-
inline const std::vector<std::string> &getNoDefaultCollisionLinks() const
Get the list of links that should have collision checking disabled by default (and only selectively enabled)
-
inline 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)
-
inline const std::vector<CollisionPair> &getDisabledCollisionPairs() const
Get the list of pairs of links for which we explicitly disable collision.
-
inline const std::vector<VirtualJoint> &getVirtualJoints() const
Get the list of virtual joints defined for this model.
-
inline const std::vector<EndEffector> &getEndEffectors() const
Get the list of end effectors defined for this model.
-
inline const std::vector<GroupState> &getGroupStates() const
Get the list of group states defined for this model.
-
inline const std::vector<PassiveJoint> &getPassiveJoints() const
Get the list of known passive joints.
-
inline const std::vector<LinkSpheres> &getLinkSphereApproximations() const
Get the collision spheres list.
-
inline const std::vector<JointProperty> &getJointProperties(const std::string &joint_name) const
Get the joint properties for a particular joint (empty vector if none)
-
inline const std::map<std::string, std::vector<JointProperty>> &getJointProperties() const
Get the joint properties list.
-
void clear()
Clear the model.
-
struct CollisionPair
The definition of a disabled/enabled collision between two links.
-
struct EndEffector
Representation of an end effector.
Public Members
-
std::string name_
The name of the end effector.
-
std::string parent_link_
The name of the link this end effector connects to.
-
std::string parent_group_
The name of the group to be considered the parent (this group should contain parent_link_) If not specified, this member is empty.
-
std::string component_group_
The name of the group that includes the joints & links this end effector consists of.
-
std::string name_
-
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.
Public Members
-
std::string name_
The name of the group.
-
std::vector<std::string> joints_
Directly specified joints to be included in the group. Descendent links should be implicitly considered to be part of the group, although this parsed does not add them to links_. The joints are checked to be in the corresponding URDF.
-
std::vector<std::string> links_
Directly specified links to be included in the group. Parent joints should be implicitly considered to be part of the group. The links are checked to be in the corresponding URDF.
-
std::vector<std::pair<std::string, std::string>> chains_
Specify a chain of links (and the implicit joints) to be added to the group. Each chain is specified as a pair of base link and tip link. It is checked that the chain is indeed a chain in the specified URDF.
-
std::vector<std::string> subgroups_
It is sometimes convenient to refer to the content of another group. A group can include the content of the referenced groups
-
std::string name_
-
struct GroupState
A named state for a particular group.
Public Members
-
std::string name_
The name of the state.
-
std::string group_
The name of the group this state is specified for.
-
std::map<std::string, std::vector<double>> joint_values_
The values of joints for this state. Each joint can have a value. We use a vector for the ‘value’ to support multi-DOF joints
-
std::string name_
-
struct JointProperty
-
struct LinkSpheres
The definition of a list of spheres for a link.
-
struct Sphere
The definition of a sphere.
-
struct VirtualJoint
In addition to the joints specified in the URDF it is sometimes convenient to add special (virtual) joints. For example, to connect the robot to the environment in a meaningful way.
Public Members
-
std::string name_
The name of the new joint.
-
std::string type_
The type of this new joint. This can be “fixed” (0 DOF), “planar” (3 DOF: x,y,yaw) or “floating” (6DOF)
-
std::string parent_frame_
The transform applied by this joint to the robot model brings that model to a particular frame.
-
std::string child_link_
The link this joint applies to.
-
std::string name_
-
inline Model()