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> // TODO: replace with urdf_model/types.h in Lunar
45 #include <memory>
46 #include <tinyxml.h>
47 
49 namespace srdf
50 {
52 class Model
53 {
54 public:
56  {
57  }
58 
60  {
61  }
62 
64  bool initXml(const urdf::ModelInterface& urdf_model, TiXmlElement* xml);
66  bool initXml(const urdf::ModelInterface& urdf_model, TiXmlDocument* 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);
71 
76  struct Group
77  {
79  std::string name_;
80 
86  std::vector<std::string> joints_;
87 
92  std::vector<std::string> links_;
93 
98  std::vector<std::pair<std::string, std::string> > chains_;
99 
103  std::vector<std::string> subgroups_;
104  };
105 
111  {
113  std::string name_;
114 
116  std::string type_;
117 
119  std::string parent_frame_;
120 
122  std::string child_link_;
123  };
124 
126  struct EndEffector
127  {
129  std::string name_;
130 
132  std::string parent_link_;
133 
136  std::string parent_group_;
137 
139  std::string component_group_;
140  };
141 
143  struct GroupState
144  {
146  std::string name_;
147 
149  std::string group_;
150 
153  std::map<std::string, std::vector<double> > joint_values_;
154  };
155 
157  struct Sphere
158  {
160  double center_x_;
161  double center_y_;
162  double center_z_;
163 
165  double radius_;
166  };
167 
169  struct LinkSpheres
170  {
172  std::string link_;
173 
175  std::vector<Sphere> spheres_;
176  };
177 
180  {
182  std::string link1_;
183 
185  std::string link2_;
186 
188  std::string reason_;
189  };
190 
191  // Some joints can be passive (not actuated). This structure specifies information about such joints
193  {
195  std::string name_;
196  };
197 
199  const std::string& getName() const
200  {
201  return name_;
202  }
203 
206  const std::vector<DisabledCollision>& getDisabledCollisionPairs() const
207  {
208  return disabled_collisions_;
209  }
210 
212  [[deprecated]] std::vector<std::pair<std::string, std::string> > getDisabledCollisions() const;
213 
215  const std::vector<Group>& getGroups() const
216  {
217  return groups_;
218  }
219 
221  const std::vector<VirtualJoint>& getVirtualJoints() const
222  {
223  return virtual_joints_;
224  }
225 
227  const std::vector<EndEffector>& getEndEffectors() const
228  {
229  return end_effectors_;
230  }
231 
233  const std::vector<GroupState>& getGroupStates() const
234  {
235  return group_states_;
236  }
237 
239  const std::vector<PassiveJoint>& getPassiveJoints() const
240  {
241  return passive_joints_;
242  }
243 
245  const std::vector<LinkSpheres>& getLinkSphereApproximations() const
246  {
248  }
249 
251  void clear();
252 
253 private:
254  void loadVirtualJoints(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
255  void loadGroups(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
256  void loadGroupStates(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
257  void loadEndEffectors(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
258  void loadLinkSphereApproximations(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
259  void loadDisabledCollisions(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
260  void loadPassiveJoints(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
261 
262  std::string name_;
263  std::vector<Group> groups_;
264  std::vector<GroupState> group_states_;
265  std::vector<VirtualJoint> virtual_joints_;
266  std::vector<EndEffector> end_effectors_;
267  std::vector<LinkSpheres> link_sphere_approximations_;
268  std::vector<DisabledCollision> disabled_collisions_;
269  std::vector<PassiveJoint> passive_joints_;
270 };
271 typedef std::shared_ptr<Model> ModelSharedPtr;
272 typedef std::shared_ptr<const Model> ModelConstSharedPtr;
273 } // namespace srdf
274 #endif
void loadVirtualJoints(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
Definition: model.cpp:46
std::vector< std::string > subgroups_
Definition: model.h:103
std::vector< VirtualJoint > virtual_joints_
Definition: model.h:265
The definition of a disabled collision between two links.
Definition: model.h:179
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:116
std::string link1_
The name of the first link (as in URDF) of the disabled collision.
Definition: model.h:182
const std::vector< PassiveJoint > & getPassiveJoints() const
Get the list of known passive joints.
Definition: model.h:239
Representation of semantic information about the robot.
Definition: model.h:52
double center_y_
Definition: model.h:161
std::string link2_
The name of the second link (as in URDF) of the disabled collision.
Definition: model.h:185
std::map< std::string, std::vector< double > > joint_values_
Definition: model.h:153
const std::vector< VirtualJoint > & getVirtualJoints() const
Get the list of virtual joints defined for this model.
Definition: model.h:221
std::vector< std::pair< std::string, std::string > > chains_
Definition: model.h:98
bool initFile(const urdf::ModelInterface &urdf_model, const std::string &filename)
Load Model given a filename.
Definition: model.cpp:638
Model()
Definition: model.h:55
std::vector< EndEffector > end_effectors_
Definition: model.h:266
void loadPassiveJoints(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
Definition: model.cpp:566
double center_z_
Definition: model.h:162
~Model()
Definition: model.h:59
const std::string & getName() const
Get the name of this model.
Definition: model.h:199
std::string name_
The name of the end effector.
Definition: model.h:129
A named state for a particular group.
Definition: model.h:143
std::vector< GroupState > group_states_
Definition: model.h:264
The definition of a list of spheres for a link.
Definition: model.h:169
std::vector< std::pair< std::string, std::string > > getDisabledCollisions() const
Definition: model.cpp:685
double center_x_
The center of the sphere in the link collision frame.
Definition: model.h:160
void loadDisabledCollisions(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
Definition: model.cpp:534
std::string name_
The name of the state.
Definition: model.h:146
std::string parent_link_
The name of the link this end effector connects to.
Definition: model.h:132
std::vector< Group > groups_
Definition: model.h:263
void loadGroupStates(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
Definition: model.cpp:283
std::string reason_
The reason why the collision check was disabled.
Definition: model.h:188
bool initString(const urdf::ModelInterface &urdf_model, const std::string &xmlstring)
Load Model from a XML-string.
Definition: model.cpp:661
std::string parent_frame_
The transform applied by this joint to the robot model brings that model to a particular frame...
Definition: model.h:119
std::string name_
Definition: model.h:262
const std::vector< LinkSpheres > & getLinkSphereApproximations() const
Get the collision spheres list.
Definition: model.h:245
std::shared_ptr< const Model > ModelConstSharedPtr
Definition: model.h:272
The definition of a sphere.
Definition: model.h:157
double radius_
The radius of the sphere.
Definition: model.h:165
Representation of an end effector.
Definition: model.h:126
std::string link_
The name of the link (as in URDF).
Definition: model.h:172
std::string name_
The name of the group.
Definition: model.h:79
std::vector< DisabledCollision > disabled_collisions_
Definition: model.h:268
Main namespace.
Definition: model.h:49
A group consists of a set of joints and the corresponding descendant links. There are multiple ways t...
Definition: model.h:76
void loadLinkSphereApproximations(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
Definition: model.cpp:437
std::vector< std::string > links_
Definition: model.h:92
void loadEndEffectors(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
Definition: model.cpp:379
const std::vector< Group > & getGroups() const
Get the list of groups defined for this model.
Definition: model.h:215
std::string child_link_
The link this joint applies to.
Definition: model.h:122
std::shared_ptr< Model > ModelSharedPtr
Definition: model.h:271
std::vector< Sphere > spheres_
The spheres for the link.
Definition: model.h:175
const std::vector< GroupState > & getGroupStates() const
Get the list of group states defined for this model.
Definition: model.h:233
std::vector< std::string > joints_
Definition: model.h:86
bool initXml(const urdf::ModelInterface &urdf_model, TiXmlElement *xml)
Load Model from TiXMLElement.
Definition: model.cpp:595
const std::vector< EndEffector > & getEndEffectors() const
Get the list of end effectors defined for this model.
Definition: model.h:227
std::vector< PassiveJoint > passive_joints_
Definition: model.h:269
std::string name_
The name of the new joint.
Definition: model.h:195
std::string component_group_
The name of the group that includes the joints & links this end effector consists of...
Definition: model.h:139
std::string name_
The name of the new joint.
Definition: model.h:113
void clear()
Clear the model.
Definition: model.cpp:673
void loadGroups(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
Definition: model.cpp:101
std::string parent_group_
Definition: model.h:136
const std::vector< DisabledCollision > & getDisabledCollisionPairs() const
Definition: model.h:206
std::string group_
The name of the group this state is specified for.
Definition: model.h:149
std::vector< LinkSpheres > link_sphere_approximations_
Definition: model.h:267


srdfdom
Author(s): Ioan Sucan , Guillaume Walck
autogenerated on Mon Feb 28 2022 23:49:16