model.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author Ioan Sucan */
36 
37 #ifndef SRDF_MODEL_
38 #define SRDF_MODEL_
39 
40 #include <map>
41 #include <string>
42 #include <vector>
43 #include <utility>
44 #include <urdf/model.h>
45 #include <memory>
46 #include <tinyxml2.h>
47 
49 namespace srdf
50 {
52 class Model
53 {
54 public:
55  using PropertyMap = std::map<std::string, std::string>; // property name -> value
56  using JointPropertyMap = std::map<std::string, PropertyMap>; // joint name -> properties
57 
58  Model()
59  {
60  }
61 
62  ~Model()
63  {
64  }
65 
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);
74 
79  struct Group
80  {
82  std::string name_;
83 
89  std::vector<std::string> joints_;
90 
95  std::vector<std::string> links_;
96 
101  std::vector<std::pair<std::string, std::string>> chains_;
102 
106  std::vector<std::string> subgroups_;
107  };
108 
113  struct VirtualJoint
114  {
116  std::string name_;
117 
119  std::string type_;
120 
122  std::string parent_frame_;
123 
125  std::string child_link_;
126  };
127 
129  struct EndEffector
130  {
132  std::string name_;
133 
135  std::string parent_link_;
136 
139  std::string parent_group_;
140 
142  std::string component_group_;
143  };
144 
146  struct GroupState
147  {
149  std::string name_;
150 
152  std::string group_;
153 
156  std::map<std::string, std::vector<double>> joint_values_;
157  };
158 
160  struct Sphere
161  {
163  double center_x_;
164  double center_y_;
165  double center_z_;
166 
168  double radius_;
169  };
170 
172  struct LinkSpheres
173  {
175  std::string link_;
176 
178  std::vector<Sphere> spheres_;
179  };
180 
182  struct CollisionPair
183  {
185  std::string link1_;
186 
188  std::string link2_;
189 
191  std::string reason_;
192  };
193 
194  // Some joints can be passive (not actuated). This structure specifies information about such joints
195  struct PassiveJoint
196  {
198  std::string name_;
199  };
200 
202  const std::string& getName() const
203  {
204  return name_;
205  }
206 
208  const std::vector<std::string>& getNoDefaultCollisionLinks() const
209  {
211  }
212 
214  const std::vector<CollisionPair>& getEnabledCollisionPairs() const
215  {
217  }
218 
220  const std::vector<CollisionPair>& getDisabledCollisionPairs() const
221  {
223  }
224 
226  const std::vector<Group>& getGroups() const
227  {
228  return groups_;
229  }
230 
232  const std::vector<VirtualJoint>& getVirtualJoints() const
233  {
234  return virtual_joints_;
235  }
236 
238  const std::vector<EndEffector>& getEndEffectors() const
239  {
240  return end_effectors_;
241  }
242 
244  const std::vector<GroupState>& getGroupStates() const
245  {
247  }
248 
250  const std::vector<PassiveJoint>& getPassiveJoints() const
251  {
253  }
254 
256  const std::vector<LinkSpheres>& getLinkSphereApproximations() const
257  {
259  }
260 
262  const PropertyMap& getJointProperties(const std::string& joint_name) const
263  {
264  static const PropertyMap empty_map;
265 
266  auto it = joint_properties_.find(joint_name);
267  if (it == joint_properties_.end())
268  return empty_map;
269  else
270  return it->second;
271  }
272 
274  const JointPropertyMap& getJointProperties() const
275  {
276  return joint_properties_;
277  }
278 
280  void clear();
281 
282 private:
283  bool isValidJoint(const urdf::ModelInterface& urdf_model, const std::string& name) const;
284 
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);
289  void loadLinkSphereApproximations(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
290  void loadCollisionDefaults(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);
295 
296  std::string name_;
297  std::vector<Group> groups_;
298  std::vector<GroupState> group_states_;
299  std::vector<VirtualJoint> virtual_joints_;
300  std::vector<EndEffector> end_effectors_;
301  std::vector<LinkSpheres> link_sphere_approximations_;
302  std::vector<std::string> no_default_collision_links_;
303  std::vector<CollisionPair> enabled_collision_pairs_;
304  std::vector<CollisionPair> disabled_collision_pairs_;
305  std::vector<PassiveJoint> passive_joints_;
307 };
308 typedef std::shared_ptr<Model> ModelSharedPtr;
309 typedef std::shared_ptr<const Model> ModelConstSharedPtr;
310 } // namespace srdf
311 #endif
srdf::Model::getEnabledCollisionPairs
const std::vector< CollisionPair > & getEnabledCollisionPairs() const
Get the list of pairs of links for which we explicitly re-enable collision (after having disabled it ...
Definition: model.h:278
srdf::Model::EndEffector::component_group_
std::string component_group_
The name of the group that includes the joints & links this end effector consists of.
Definition: model.h:206
srdf::Model::EndEffector::name_
std::string name_
The name of the end effector.
Definition: model.h:196
srdf::Model::passive_joints_
std::vector< PassiveJoint > passive_joints_
Definition: model.h:369
srdf::Model::JointPropertyMap
std::map< std::string, PropertyMap > JointPropertyMap
Definition: model.h:120
srdf::Model::VirtualJoint::name_
std::string name_
The name of the new joint.
Definition: model.h:180
srdf::Model::virtual_joints_
std::vector< VirtualJoint > virtual_joints_
Definition: model.h:363
srdf::Model::Group::chains_
std::vector< std::pair< std::string, std::string > > chains_
Definition: model.h:165
srdf::Model::PropertyMap
std::map< std::string, std::string > PropertyMap
Definition: model.h:119
srdf::Model::loadGroups
void loadGroups(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:119
srdf::Model::getPassiveJoints
const std::vector< PassiveJoint > & getPassiveJoints() const
Get the list of known passive joints.
Definition: model.h:314
srdf::ModelSharedPtr
std::shared_ptr< Model > ModelSharedPtr
Definition: model.h:340
srdf::Model::link_sphere_approximations_
std::vector< LinkSpheres > link_sphere_approximations_
Definition: model.h:365
srdf::Model::~Model
~Model()
Definition: model.h:126
srdf::Model::loadGroupStates
void loadGroupStates(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:290
srdf::Model::getNoDefaultCollisionLinks
const std::vector< std::string > & getNoDefaultCollisionLinks() const
Get the list of links that should have collision checking disabled by default (and only selectively e...
Definition: model.h:272
srdf::Model::initXml
bool initXml(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *xml)
Load Model from XMLElement.
srdf::Model::LinkSpheres
The definition of a list of spheres for a link.
Definition: model.h:236
srdf::Model::disabled_collision_pairs_
std::vector< CollisionPair > disabled_collision_pairs_
Definition: model.h:368
srdf::Model::PassiveJoint::name_
std::string name_
The name of the new joint.
Definition: model.h:262
srdf::Model::name_
std::string name_
Definition: model.h:360
srdf::Model::clear
void clear()
Clear the model.
Definition: model.cpp:717
srdf::Model::loadEndEffectors
void loadEndEffectors(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:376
srdf::Model::VirtualJoint::parent_frame_
std::string parent_frame_
The transform applied by this joint to the robot model brings that model to a particular frame.
Definition: model.h:186
srdf::Model::CollisionPair::link2_
std::string link2_
The name of the second link (as in URDF) of the disabled collision.
Definition: model.h:252
srdf::Model::initString
bool initString(const urdf::ModelInterface &urdf_model, const std::string &xmlstring)
Load Model from a XML-string.
Definition: model.cpp:706
srdf::Model::Sphere::center_z_
double center_z_
Definition: model.h:229
srdf::Model::group_states_
std::vector< GroupState > group_states_
Definition: model.h:362
srdf::Model::getGroupStates
const std::vector< GroupState > & getGroupStates() const
Get the list of group states defined for this model.
Definition: model.h:308
srdf::Model::Group::name_
std::string name_
The name of the group.
Definition: model.h:146
srdf::Model::GroupState::group_
std::string group_
The name of the group this state is specified for.
Definition: model.h:216
srdf::Model::EndEffector::parent_link_
std::string parent_link_
The name of the link this end effector connects to.
Definition: model.h:199
srdf::Model::isValidJoint
bool isValidJoint(const urdf::ModelInterface &urdf_model, const std::string &name) const
Definition: model.cpp:48
srdf::Model::loadCollisionPairs
void loadCollisionPairs(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml, const char *tag_name, std::vector< CollisionPair > &pairs)
Definition: model.cpp:552
srdf::Model::loadPassiveJoints
void loadPassiveJoints(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:582
srdf::Model::getJointProperties
const JointPropertyMap & getJointProperties() const
Get the joint properties map.
Definition: model.h:338
model.h
srdf::ModelConstSharedPtr
std::shared_ptr< const Model > ModelConstSharedPtr
Definition: model.h:341
srdf::Model::Group::links_
std::vector< std::string > links_
Definition: model.h:159
srdf::Model::initFile
bool initFile(const urdf::ModelInterface &urdf_model, const std::string &filename)
Load Model given a filename.
Definition: model.cpp:683
srdf::Model::end_effectors_
std::vector< EndEffector > end_effectors_
Definition: model.h:364
srdf::Model::Sphere::center_y_
double center_y_
Definition: model.h:228
srdf::Model::loadCollisionDefaults
void loadCollisionDefaults(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:531
srdf::Model::getGroups
const std::vector< Group > & getGroups() const
Get the list of groups defined for this model.
Definition: model.h:290
srdf::Model::loadLinkSphereApproximations
void loadLinkSphereApproximations(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:434
srdf::Model::no_default_collision_links_
std::vector< std::string > no_default_collision_links_
Definition: model.h:366
srdf::Model::loadJointProperties
void loadJointProperties(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:605
srdf::Model::LinkSpheres::spheres_
std::vector< Sphere > spheres_
The spheres for the link.
Definition: model.h:242
srdf::Model::Model
Model()
Definition: model.h:122
srdf::Model::PassiveJoint
Definition: model.h:259
srdf::Model::GroupState::joint_values_
std::map< std::string, std::vector< double > > joint_values_
Definition: model.h:220
srdf::Model::groups_
std::vector< Group > groups_
Definition: model.h:361
srdf::Model::GroupState
A named state for a particular group.
Definition: model.h:210
srdf::Model::Sphere
The definition of a sphere.
Definition: model.h:224
srdf::Model::joint_properties_
JointPropertyMap joint_properties_
Definition: model.h:370
srdf::Model::enabled_collision_pairs_
std::vector< CollisionPair > enabled_collision_pairs_
Definition: model.h:367
srdf::Model::Sphere::center_x_
double center_x_
The center of the sphere in the link collision frame.
Definition: model.h:227
srdf::Model::getDisabledCollisionPairs
const std::vector< CollisionPair > & getDisabledCollisionPairs() const
Get the list of pairs of links for which we explicitly disable collision.
Definition: model.h:284
srdf
Main namespace.
Definition: model.h:49
srdf::Model::VirtualJoint::child_link_
std::string child_link_
The link this joint applies to.
Definition: model.h:189
srdf::Model::EndEffector::parent_group_
std::string parent_group_
Definition: model.h:203
srdf::Model::getEndEffectors
const std::vector< EndEffector > & getEndEffectors() const
Get the list of end effectors defined for this model.
Definition: model.h:302
srdf::Model::GroupState::name_
std::string name_
The name of the state.
Definition: model.h:213
srdf::Model::LinkSpheres::link_
std::string link_
The name of the link (as in URDF).
Definition: model.h:239
srdf::Model::Group::subgroups_
std::vector< std::string > subgroups_
Definition: model.h:170
srdf::Model::loadVirtualJoints
void loadVirtualJoints(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:64
srdf::Model::getLinkSphereApproximations
const std::vector< LinkSpheres > & getLinkSphereApproximations() const
Get the collision spheres list.
Definition: model.h:320
srdf::Model::Sphere::radius_
double radius_
The radius of the sphere.
Definition: model.h:232
srdf::Model::CollisionPair
The definition of a disabled/enabled collision between two links.
Definition: model.h:246
srdf::Model::getName
const std::string & getName() const
Get the name of this model.
Definition: model.h:266
srdf::Model::Group::joints_
std::vector< std::string > joints_
Definition: model.h:153
srdf::Model::CollisionPair::reason_
std::string reason_
The reason why the collision check was disabled/enabled.
Definition: model.h:255
srdf::Model::getVirtualJoints
const std::vector< VirtualJoint > & getVirtualJoints() const
Get the list of virtual joints defined for this model.
Definition: model.h:296
srdf::Model::CollisionPair::link1_
std::string link1_
The name of the first link (as in URDF) of the disabled collision.
Definition: model.h:249
srdf::Model::VirtualJoint::type_
std::string type_
The type of this new joint. This can be "fixed" (0 DOF), "planar" (3 DOF: x,y,yaw) or "floating" (6DO...
Definition: model.h:183
srdf::Model
Representation of semantic information about the robot.
Definition: model.h:84


srdfdom
Author(s): Ioan Sucan , Guillaume Walck
autogenerated on Fri Jul 7 2023 02:22:48