Go to the documentation of this file.
64 bool initXml(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* xml);
66 bool initXml(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLDocument* xml);
68 bool initFile(
const urdf::ModelInterface& urdf_model,
const std::string& filename);
70 bool initString(
const urdf::ModelInterface& urdf_model,
const std::string& xmlstring);
86 std::vector<std::string>
joints_;
92 std::vector<std::string>
links_;
98 std::vector<std::pair<std::string, std::string> >
chains_;
199 const std::string&
getName()
const
215 const std::vector<Group>&
getGroups()
const
254 void loadVirtualJoints(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
255 void loadGroups(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
256 void loadGroupStates(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
257 void loadEndEffectors(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
260 void loadPassiveJoints(
const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
std::vector< std::pair< std::string, std::string > > getDisabledCollisions() const
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.
const std::vector< DisabledCollision > & getDisabledCollisionPairs() const
std::vector< PassiveJoint > passive_joints_
std::string name_
The name of the new joint.
std::vector< VirtualJoint > virtual_joints_
std::vector< DisabledCollision > disabled_collisions_
std::vector< std::pair< std::string, std::string > > chains_
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)
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::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.
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.
void loadPassiveJoints(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
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_
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< 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.
std::string reason_
The reason why the collision check was disabled.
double center_x_
The center of the sphere in the link collision frame.
std::string child_link_
The link this joint applies to.
std::string parent_group_
void loadDisabledCollisions(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
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)
The definition of a disabled collision between two links.
const std::vector< LinkSpheres > & getLinkSphereApproximations() const
Get the collision spheres list.
double radius_
The radius of the sphere.
std::string link1_
The name of the first link (as in URDF) of the disabled collision.
std::string link2_
The name of the second link (as in URDF) of the disabled collision.
const std::string & getName() const
Get the name of this model.
std::vector< std::string > joints_
const std::vector< VirtualJoint > & getVirtualJoints() const
Get the list of virtual joints defined for this model.
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 Mon Oct 19 2020 03:26:07