Go to the documentation of this file.
55 using PropertyMap = std::map<std::string, std::string>;
67 bool initXml(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* xml);
69 bool initXml(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLDocument* xml);
71 bool initFile(
const urdf::ModelInterface& urdf_model,
const std::string& filename);
73 bool initString(
const urdf::ModelInterface& urdf_model,
const std::string& xmlstring);
89 std::vector<std::string>
joints_;
95 std::vector<std::string>
links_;
101 std::vector<std::pair<std::string, std::string>>
chains_;
202 const std::string&
getName()
const
226 const std::vector<Group>&
getGroups()
const
283 bool isValidJoint(
const urdf::ModelInterface& urdf_model,
const std::string& name)
const;
285 void loadVirtualJoints(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
286 void loadGroups(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
287 void loadGroupStates(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
288 void loadEndEffectors(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
291 void loadCollisionPairs(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml,
const char* tag_name,
292 std::vector<CollisionPair>& pairs);
293 void loadPassiveJoints(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
294 void loadJointProperties(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
const std::vector< CollisionPair > & getEnabledCollisionPairs() const
Get the list of pairs of links for which we explicitly re-enable collision (after having disabled it ...
std::string component_group_
The name of the group that includes the joints & links this end effector consists of.
std::string name_
The name of the end effector.
std::vector< PassiveJoint > passive_joints_
std::map< std::string, PropertyMap > JointPropertyMap
std::string name_
The name of the new joint.
std::vector< VirtualJoint > virtual_joints_
std::vector< std::pair< std::string, std::string > > chains_
std::map< std::string, std::string > PropertyMap
void loadGroups(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
const std::vector< PassiveJoint > & getPassiveJoints() const
Get the list of known passive joints.
std::shared_ptr< Model > ModelSharedPtr
std::vector< LinkSpheres > link_sphere_approximations_
void loadGroupStates(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
const std::vector< std::string > & getNoDefaultCollisionLinks() const
Get the list of links that should have collision checking disabled by default (and only selectively e...
bool initXml(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *xml)
Load Model from XMLElement.
The definition of a list of spheres for a link.
std::vector< CollisionPair > disabled_collision_pairs_
std::string name_
The name of the new joint.
void clear()
Clear the model.
void loadEndEffectors(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
std::string parent_frame_
The transform applied by this joint to the robot model brings that model to a particular frame.
std::string link2_
The name of the second link (as in URDF) of the disabled collision.
bool initString(const urdf::ModelInterface &urdf_model, const std::string &xmlstring)
Load Model from a XML-string.
std::vector< GroupState > group_states_
const std::vector< GroupState > & getGroupStates() const
Get the list of group states defined for this model.
std::string name_
The name of the group.
std::string group_
The name of the group this state is specified for.
std::string parent_link_
The name of the link this end effector connects to.
bool isValidJoint(const urdf::ModelInterface &urdf_model, const std::string &name) const
void loadCollisionPairs(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml, const char *tag_name, std::vector< CollisionPair > &pairs)
void loadPassiveJoints(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
const JointPropertyMap & getJointProperties() const
Get the joint properties map.
std::shared_ptr< const Model > ModelConstSharedPtr
std::vector< std::string > links_
bool initFile(const urdf::ModelInterface &urdf_model, const std::string &filename)
Load Model given a filename.
std::vector< EndEffector > end_effectors_
void loadCollisionDefaults(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
const std::vector< Group > & getGroups() const
Get the list of groups defined for this model.
void loadLinkSphereApproximations(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
std::vector< std::string > no_default_collision_links_
void loadJointProperties(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
std::vector< Sphere > spheres_
The spheres for the link.
std::map< std::string, std::vector< double > > joint_values_
std::vector< Group > groups_
A named state for a particular group.
The definition of a sphere.
JointPropertyMap joint_properties_
std::vector< CollisionPair > enabled_collision_pairs_
double center_x_
The center of the sphere in the link collision frame.
const std::vector< CollisionPair > & getDisabledCollisionPairs() const
Get the list of pairs of links for which we explicitly disable collision.
std::string child_link_
The link this joint applies to.
std::string parent_group_
const std::vector< EndEffector > & getEndEffectors() const
Get the list of end effectors defined for this model.
std::string name_
The name of the state.
std::string link_
The name of the link (as in URDF).
std::vector< std::string > subgroups_
void loadVirtualJoints(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
const std::vector< LinkSpheres > & getLinkSphereApproximations() const
Get the collision spheres list.
double radius_
The radius of the sphere.
The definition of a disabled/enabled collision between two links.
const std::string & getName() const
Get the name of this model.
std::vector< std::string > joints_
std::string reason_
The reason why the collision check was disabled/enabled.
const std::vector< VirtualJoint > & getVirtualJoints() const
Get the list of virtual joints defined for this model.
std::string link1_
The name of the first link (as in URDF) of the disabled collision.
std::string type_
The type of this new joint. This can be "fixed" (0 DOF), "planar" (3 DOF: x,y,yaw) or "floating" (6DO...
Representation of semantic information about the robot.
srdfdom
Author(s): Ioan Sucan
, Guillaume Walck
autogenerated on Wed Oct 16 2024 02:22:59