45 #include <boost/shared_ptr.hpp> 66 bool initXml(
const urdf::ModelInterface &urdf_model, TiXmlElement *xml);
68 bool initXml(
const urdf::ModelInterface &urdf_model, TiXmlDocument *xml);
70 bool initFile(
const urdf::ModelInterface &urdf_model,
const std::string& filename);
72 bool initString(
const urdf::ModelInterface &urdf_model,
const std::string& xmlstring);
100 std::vector<std::pair<std::string, std::string> >
chains_;
212 __attribute__ ((deprecated))
213 std::vector<std::pair<std::string, std::string> > getDisabledCollisions()
const;
256 void loadVirtualJoints(
const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
257 void loadGroups(
const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
258 void loadGroupStates(
const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
259 void loadEndEffectors(
const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
262 void loadPassiveJoints(
const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
void loadVirtualJoints(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::vector< std::string > subgroups_
std::vector< VirtualJoint > virtual_joints_
The definition of a disabled collision between two links.
std::string type_
The type of this new joint. This can be "fixed" (0 DOF), "planar" (3 DOF: x,y,yaw) or "floating" (6DO...
std::string link1_
The name of the first link (as in URDF) of the disabled collision.
Representation of semantic information about the robot.
std::string link2_
The name of the second link (as in URDF) of the disabled collision.
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 ...
const std::vector< VirtualJoint > & getVirtualJoints() const
Get the list of virtual joints defined for this model.
std::vector< std::pair< std::string, std::string > > chains_
bool initFile(const urdf::ModelInterface &urdf_model, const std::string &filename)
Load Model given a filename.
std::vector< EndEffector > end_effectors_
void loadPassiveJoints(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::string name_
The name of the end effector.
A named state for a particular group.
std::vector< GroupState > group_states_
The definition of a list of spheres for a link.
double center_x_
The center of the sphere in the link collision frame.
void loadDisabledCollisions(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::string name_
The name of the state.
std::string parent_link_
The name of the link this end effector connects to.
__attribute__((deprecated)) std const std::vector< Group > & getGroups() const
Get the list of groups defined for this model.
std::vector< Group > groups_
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 ...
const std::string & getName() const
Get the name of this model.
void loadGroupStates(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::string reason_
The reason why the collision check was disabled.
bool initString(const urdf::ModelInterface &urdf_model, const std::string &xmlstring)
Load Model from a XML-string.
std::string parent_frame_
The transform applied by this joint to the robot model brings that model to a particular frame...
The definition of a sphere.
double radius_
The radius of the sphere.
Representation of an end effector.
std::string link_
The name of the link (as in URDF).
boost::shared_ptr< Model > ModelSharedPtr
std::string name_
The name of the group.
std::vector< DisabledCollision > disabled_collisions_
A group consists of a set of joints and the corresponding descendant links. There are multiple ways t...
void loadLinkSphereApproximations(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::vector< std::string > links_
void loadEndEffectors(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::string child_link_
The link this joint applies to.
const std::vector< LinkSpheres > & getLinkSphereApproximations() const
Get the collision spheres list.
const std::vector< PassiveJoint > & getPassiveJoints() const
Get the list of known passive joints.
std::vector< Sphere > spheres_
The spheres for the link.
std::vector< std::string > joints_
bool initXml(const urdf::ModelInterface &urdf_model, TiXmlElement *xml)
Load Model from TiXMLElement.
std::vector< PassiveJoint > passive_joints_
std::string name_
The name of the new joint.
boost::shared_ptr< const Model > ModelConstSharedPtr
const std::vector< GroupState > & getGroupStates() const
Get the list of group states defined for this model.
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 new joint.
void clear()
Clear the model.
void loadGroups(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
const std::vector< EndEffector > & getEndEffectors() const
Get the list of end effectors defined for this model.
std::string parent_group_
std::string group_
The name of the group this state is specified for.
std::vector< LinkSpheres > link_sphere_approximations_