model.cpp
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 #include "srdfdom/model.h"
38 #include <console_bridge/console.h>
39 #include <boost/algorithm/string/trim.hpp>
40 #include <algorithm>
41 #include <fstream>
42 #include <sstream>
43 #include <set>
44 #include <limits>
45 
46 using namespace tinyxml2;
47 
48 bool srdf::Model::isValidJoint(const urdf::ModelInterface& urdf_model, const std::string& name) const
49 {
50  if (urdf_model.getJoint(name))
51  {
52  return true;
53  }
54  for (const srdf::Model::VirtualJoint& vj : virtual_joints_)
55  {
56  if (vj.name_ == name)
57  {
58  return true;
59  }
60  }
61  return false;
62 }
63 
64 void srdf::Model::loadVirtualJoints(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
65 {
66  for (XMLElement* vj_xml = robot_xml->FirstChildElement("virtual_joint"); vj_xml;
67  vj_xml = vj_xml->NextSiblingElement("virtual_joint"))
68  {
69  const char* jname = vj_xml->Attribute("name");
70  const char* child = vj_xml->Attribute("child_link");
71  const char* parent = vj_xml->Attribute("parent_frame");
72  const char* type = vj_xml->Attribute("type");
73  if (!jname)
74  {
75  CONSOLE_BRIDGE_logError("Name of virtual joint is not specified");
76  continue;
77  }
78  if (!child)
79  {
80  CONSOLE_BRIDGE_logError("Child link of virtual joint is not specified");
81  continue;
82  }
83  if (!urdf_model.getLink(boost::trim_copy(std::string(child))))
84  {
85  CONSOLE_BRIDGE_logError("Virtual joint does not attach to a link on the robot (link '%s' is not known)", child);
86  continue;
87  }
88  if (!parent)
89  {
90  CONSOLE_BRIDGE_logError("Parent frame of virtual joint is not specified");
91  continue;
92  }
93  if (!type)
94  {
95  CONSOLE_BRIDGE_logError("Type of virtual joint is not specified");
96  continue;
97  }
98  VirtualJoint vj;
99  vj.type_ = std::string(type);
100  boost::trim(vj.type_);
101  std::transform(vj.type_.begin(), vj.type_.end(), vj.type_.begin(), ::tolower);
102  if (vj.type_ != "planar" && vj.type_ != "floating" && vj.type_ != "fixed")
103  {
104  CONSOLE_BRIDGE_logError("Unknown type of joint: '%s'. Assuming 'fixed' instead. Other known types are 'planar' "
105  "and 'floating'.",
106  type);
107  vj.type_ = "fixed";
108  }
109  vj.name_ = std::string(jname);
110  boost::trim(vj.name_);
111  vj.child_link_ = std::string(child);
112  boost::trim(vj.child_link_);
113  vj.parent_frame_ = std::string(parent);
114  boost::trim(vj.parent_frame_);
115  virtual_joints_.push_back(vj);
116  }
117 }
118 
119 void srdf::Model::loadGroups(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
120 {
121  for (XMLElement* group_xml = robot_xml->FirstChildElement("group"); group_xml;
122  group_xml = group_xml->NextSiblingElement("group"))
123  {
124  const char* gname = group_xml->Attribute("name");
125  if (!gname)
126  {
127  CONSOLE_BRIDGE_logError("Group name not specified");
128  continue;
129  }
130  Group g;
131  g.name_ = std::string(gname);
132  boost::trim(g.name_);
133 
134  // get the links in the groups
135  for (XMLElement* link_xml = group_xml->FirstChildElement("link"); link_xml;
136  link_xml = link_xml->NextSiblingElement("link"))
137  {
138  const char* lname = link_xml->Attribute("name");
139  if (!lname)
140  {
141  CONSOLE_BRIDGE_logError("Link name not specified");
142  continue;
143  }
144  std::string lname_str = boost::trim_copy(std::string(lname));
145  if (!urdf_model.getLink(lname_str))
146  {
147  CONSOLE_BRIDGE_logError("Link '%s' declared as part of group '%s' is not known to the URDF", lname, gname);
148  continue;
149  }
150  g.links_.push_back(lname_str);
151  }
152 
153  // get the joints in the groups
154  for (XMLElement* joint_xml = group_xml->FirstChildElement("joint"); joint_xml;
155  joint_xml = joint_xml->NextSiblingElement("joint"))
156  {
157  const char* jname = joint_xml->Attribute("name");
158  if (!jname)
159  {
160  CONSOLE_BRIDGE_logError("Joint name not specified");
161  continue;
162  }
163  std::string jname_str = boost::trim_copy(std::string(jname));
164  if (!isValidJoint(urdf_model, jname_str))
165  {
166  CONSOLE_BRIDGE_logError("Joint '%s' declared as part of group '%s' is not known to the URDF", jname, gname);
167  continue;
168  }
169  g.joints_.push_back(jname_str);
170  }
171 
172  // get the chains in the groups
173  for (XMLElement* chain_xml = group_xml->FirstChildElement("chain"); chain_xml;
174  chain_xml = chain_xml->NextSiblingElement("chain"))
175  {
176  const char* base = chain_xml->Attribute("base_link");
177  const char* tip = chain_xml->Attribute("tip_link");
178  if (!base)
179  {
180  CONSOLE_BRIDGE_logError("Base link name not specified for chain");
181  continue;
182  }
183  if (!tip)
184  {
185  CONSOLE_BRIDGE_logError("Tip link name not specified for chain");
186  continue;
187  }
188  std::string base_str = boost::trim_copy(std::string(base));
189  std::string tip_str = boost::trim_copy(std::string(tip));
190  if (!urdf_model.getLink(base_str))
191  {
192  CONSOLE_BRIDGE_logError("Link '%s' declared as part of a chain in group '%s' is not known to the URDF", base,
193  gname);
194  continue;
195  }
196  if (!urdf_model.getLink(tip_str))
197  {
198  CONSOLE_BRIDGE_logError("Link '%s' declared as part of a chain in group '%s' is not known to the URDF", tip,
199  gname);
200  continue;
201  }
202  bool found = false;
203  urdf::LinkConstSharedPtr l = urdf_model.getLink(tip_str);
204  std::set<std::string> seen;
205  while (!found && l)
206  {
207  seen.insert(l->name);
208  if (l->name == base_str)
209  found = true;
210  else
211  l = l->getParent();
212  }
213  if (!found)
214  {
215  l = urdf_model.getLink(base_str);
216  while (!found && l)
217  {
218  if (seen.find(l->name) != seen.end())
219  found = true;
220  else
221  l = l->getParent();
222  }
223  }
224  if (found)
225  g.chains_.push_back(std::make_pair(base_str, tip_str));
226  else
227  CONSOLE_BRIDGE_logError("Links '%s' and '%s' do not form a chain. Not included in group '%s'", base, tip, gname);
228  }
229 
230  // get the subgroups in the groups
231  for (XMLElement* subg_xml = group_xml->FirstChildElement("group"); subg_xml;
232  subg_xml = subg_xml->NextSiblingElement("group"))
233  {
234  const char* sub = subg_xml->Attribute("name");
235  if (!sub)
236  {
237  CONSOLE_BRIDGE_logError("Group name not specified when included as subgroup");
238  continue;
239  }
240  g.subgroups_.push_back(boost::trim_copy(std::string(sub)));
241  }
242  if (g.links_.empty() && g.joints_.empty() && g.chains_.empty() && g.subgroups_.empty())
243  CONSOLE_BRIDGE_logWarn("Group '%s' is empty.", gname);
244  groups_.push_back(g);
245  }
246 
247  // check the subgroups
248  std::set<std::string> known_groups;
249  bool update = true;
250  while (update)
251  {
252  update = false;
253  for (std::size_t i = 0; i < groups_.size(); ++i)
254  {
255  if (known_groups.find(groups_[i].name_) != known_groups.end())
256  continue;
257  if (groups_[i].subgroups_.empty())
258  {
259  known_groups.insert(groups_[i].name_);
260  update = true;
261  }
262  else
263  {
264  bool ok = true;
265  for (std::size_t j = 0; ok && j < groups_[i].subgroups_.size(); ++j)
266  if (known_groups.find(groups_[i].subgroups_[j]) == known_groups.end())
267  ok = false;
268  if (ok)
269  {
270  known_groups.insert(groups_[i].name_);
271  update = true;
272  }
273  }
274  }
275  }
276 
277  // if there are erroneous groups, keep only the valid ones
278  if (known_groups.size() != groups_.size())
279  {
280  std::vector<Group> correct;
281  for (std::size_t i = 0; i < groups_.size(); ++i)
282  if (known_groups.find(groups_[i].name_) != known_groups.end())
283  correct.push_back(groups_[i]);
284  else
285  CONSOLE_BRIDGE_logError("Group '%s' has unsatisfied subgroups", groups_[i].name_.c_str());
286  groups_.swap(correct);
287  }
288 }
289 
290 void srdf::Model::loadGroupStates(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
291 {
292  for (XMLElement* gstate_xml = robot_xml->FirstChildElement("group_state"); gstate_xml;
293  gstate_xml = gstate_xml->NextSiblingElement("group_state"))
294  {
295  const char* sname = gstate_xml->Attribute("name");
296  const char* gname = gstate_xml->Attribute("group");
297  if (!sname)
298  {
299  CONSOLE_BRIDGE_logError("Name of group state is not specified");
300  continue;
301  }
302  if (!gname)
303  {
304  CONSOLE_BRIDGE_logError("Name of group for state '%s' is not specified", sname);
305  continue;
306  }
307 
308  GroupState gs;
309  gs.name_ = boost::trim_copy(std::string(sname));
310  gs.group_ = boost::trim_copy(std::string(gname));
311 
312  bool found = false;
313  for (std::size_t k = 0; k < groups_.size(); ++k)
314  if (groups_[k].name_ == gs.group_)
315  {
316  found = true;
317  break;
318  }
319  if (!found)
320  {
321  CONSOLE_BRIDGE_logError("Group state '%s' specified for group '%s', but that group is not known", sname, gname);
322  continue;
323  }
324 
325  // get the joint values in the group state
326  for (XMLElement* joint_xml = gstate_xml->FirstChildElement("joint"); joint_xml;
327  joint_xml = joint_xml->NextSiblingElement("joint"))
328  {
329  const char* jname = joint_xml->Attribute("name");
330  const char* jval = joint_xml->Attribute("value");
331  if (!jname)
332  {
333  CONSOLE_BRIDGE_logError("Joint name not specified in group state '%s'", sname);
334  continue;
335  }
336  if (!jval)
337  {
338  CONSOLE_BRIDGE_logError("Joint name not specified for joint '%s' in group state '%s'", jname, sname);
339  continue;
340  }
341  std::string jname_str = boost::trim_copy(std::string(jname));
342  if (!isValidJoint(urdf_model, jname_str))
343  {
344  CONSOLE_BRIDGE_logError("Joint '%s' declared as part of group state '%s' is not known to the URDF", jname,
345  sname);
346  continue;
347  }
348  try
349  {
350  std::string jval_str = std::string(jval);
351  std::istringstream ss(jval_str);
352  while (ss.good() && !ss.eof())
353  {
354  double val;
355  ss >> val >> std::ws;
356  gs.joint_values_[jname_str].push_back(val);
357  }
358  }
359  catch (const std::invalid_argument& e)
360  {
361  CONSOLE_BRIDGE_logError("Unable to parse joint value '%s'", jval);
362  }
363  catch (const std::out_of_range& e)
364  {
365  CONSOLE_BRIDGE_logError("Unable to parse joint value '%s' (out of range)", jval);
366  }
367 
368  if (gs.joint_values_.empty())
369  CONSOLE_BRIDGE_logError("Unable to parse joint value ('%s') for joint '%s' in group state '%s'", jval, jname,
370  sname);
371  }
372  group_states_.push_back(gs);
373  }
374 }
375 
376 void srdf::Model::loadEndEffectors(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
377 {
378  for (XMLElement* eef_xml = robot_xml->FirstChildElement("end_effector"); eef_xml;
379  eef_xml = eef_xml->NextSiblingElement("end_effector"))
380  {
381  const char* ename = eef_xml->Attribute("name");
382  const char* gname = eef_xml->Attribute("group");
383  const char* parent = eef_xml->Attribute("parent_link");
384  const char* parent_group = eef_xml->Attribute("parent_group");
385  if (!ename)
386  {
387  CONSOLE_BRIDGE_logError("Name of end effector is not specified");
388  continue;
389  }
390  if (!gname)
391  {
392  CONSOLE_BRIDGE_logError("Group not specified for end effector '%s'", ename);
393  continue;
394  }
395  EndEffector e;
396  e.name_ = std::string(ename);
397  boost::trim(e.name_);
398  e.component_group_ = std::string(gname);
399  boost::trim(e.component_group_);
400  bool found = false;
401  for (std::size_t k = 0; k < groups_.size(); ++k)
402  if (groups_[k].name_ == e.component_group_)
403  {
404  found = true;
405  break;
406  }
407  if (!found)
408  {
409  CONSOLE_BRIDGE_logError("End effector '%s' specified for group '%s', but that group is not known", ename, gname);
410  continue;
411  }
412  if (!parent)
413  {
414  CONSOLE_BRIDGE_logError("Parent link not specified for end effector '%s'", ename);
415  continue;
416  }
417  e.parent_link_ = std::string(parent);
418  boost::trim(e.parent_link_);
419  if (!urdf_model.getLink(e.parent_link_))
420  {
421  CONSOLE_BRIDGE_logError("Link '%s' specified as parent for end effector '%s' is not known to the URDF", parent,
422  ename);
423  continue;
424  }
425  if (parent_group)
426  {
427  e.parent_group_ = std::string(parent_group);
428  boost::trim(e.parent_group_);
429  }
430  end_effectors_.push_back(e);
431  }
432 }
433 
434 void srdf::Model::loadLinkSphereApproximations(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
435 {
436  for (XMLElement* cslink_xml = robot_xml->FirstChildElement("link_sphere_approximation"); cslink_xml;
437  cslink_xml = cslink_xml->NextSiblingElement("link_sphere_approximation"))
438  {
439  int non_0_radius_sphere_cnt = 0;
440  const char* link_name = cslink_xml->Attribute("link");
441  if (!link_name)
442  {
443  CONSOLE_BRIDGE_logError("Name of link is not specified in link_collision_spheres");
444  continue;
445  }
446 
447  LinkSpheres link_spheres;
448  link_spheres.link_ = boost::trim_copy(std::string(link_name));
449  if (!urdf_model.getLink(link_spheres.link_))
450  {
451  CONSOLE_BRIDGE_logError("Link '%s' is not known to URDF.", link_name);
452  continue;
453  }
454 
455  // get the spheres for this link
456  int cnt = 0;
457  for (XMLElement* sphere_xml = cslink_xml->FirstChildElement("sphere"); sphere_xml;
458  sphere_xml = sphere_xml->NextSiblingElement("sphere"), cnt++)
459  {
460  const char* s_center = sphere_xml->Attribute("center");
461  const char* s_r = sphere_xml->Attribute("radius");
462  if (!s_center || !s_r)
463  {
464  CONSOLE_BRIDGE_logError("Link collision sphere %d for link '%s' does not have both center and radius.", cnt,
465  link_name);
466  continue;
467  }
468 
469  Sphere sphere;
470  try
471  {
472  std::stringstream center(s_center);
473  center.exceptions(std::stringstream::failbit | std::stringstream::badbit);
474  center >> sphere.center_x_ >> sphere.center_y_ >> sphere.center_z_;
475  sphere.radius_ = std::stod(s_r);
476  }
477  catch (std::stringstream::failure& e)
478  {
479  CONSOLE_BRIDGE_logError("Link collision sphere %d for link '%s' has bad center attribute value.", cnt,
480  link_name);
481  continue;
482  }
483  catch (const std::invalid_argument& e)
484  {
485  CONSOLE_BRIDGE_logError("Link collision sphere %d for link '%s' has bad radius attribute value.", cnt,
486  link_name);
487  continue;
488  }
489  catch (const std::out_of_range& e)
490  {
491  CONSOLE_BRIDGE_logError("Link collision sphere %d for link '%s' has an out of range radius attribute value.",
492  cnt, link_name);
493  continue;
494  }
495 
496  // ignore radius==0 spheres unless there is only 1 of them
497  //
498  // NOTE:
499  // - If a link has no sphere_approximation then one will be generated
500  // automatically containing a single sphere which encloses the entire
501  // collision geometry. Internally this is represented by not having
502  // a link_sphere_approximations_ entry for this link.
503  // - If a link has only spheres with radius 0 then it will not be
504  // considered for collision detection. In this case the internal
505  // representation is a single radius=0 sphere.
506  // - If a link has at least one sphere with radius>0 then those spheres
507  // are used. Any radius=0 spheres are eliminated.
508  if (sphere.radius_ > std::numeric_limits<double>::epsilon())
509  {
510  if (non_0_radius_sphere_cnt == 0)
511  link_spheres.spheres_.clear();
512  link_spheres.spheres_.push_back(sphere);
513  non_0_radius_sphere_cnt++;
514  }
515  else if (non_0_radius_sphere_cnt == 0)
516  {
517  sphere.center_x_ = 0.0;
518  sphere.center_y_ = 0.0;
519  sphere.center_z_ = 0.0;
520  sphere.radius_ = 0.0;
521  link_spheres.spheres_.clear();
522  link_spheres.spheres_.push_back(sphere);
523  }
524  }
525 
526  if (!link_spheres.spheres_.empty())
527  link_sphere_approximations_.push_back(link_spheres);
528  }
529 }
530 
531 void srdf::Model::loadCollisionDefaults(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
532 {
533  for (XMLElement* xml = robot_xml->FirstChildElement("disable_default_collisions"); xml;
534  xml = xml->NextSiblingElement("disable_default_collisions"))
535  {
536  const char* link_ = xml->Attribute("link");
537  if (!link_)
538  {
539  CONSOLE_BRIDGE_logError("A disable_default_collisions tag needs to specify a link name");
540  continue;
541  }
542  std::string link = boost::trim_copy(std::string(link_));
543  if (!urdf_model.getLink(link))
544  {
545  CONSOLE_BRIDGE_logWarn("Link '%s' is not known to URDF. Cannot specify collision default.", link_);
546  continue;
547  }
548  no_default_collision_links_.push_back(link);
549  }
550 }
551 
552 void srdf::Model::loadCollisionPairs(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml,
553  const char* tag_name, std::vector<CollisionPair>& pairs)
554 {
555  for (XMLElement* c_xml = robot_xml->FirstChildElement(tag_name); c_xml; c_xml = c_xml->NextSiblingElement(tag_name))
556  {
557  const char* link1 = c_xml->Attribute("link1");
558  const char* link2 = c_xml->Attribute("link2");
559  if (!link1 || !link2)
560  {
561  CONSOLE_BRIDGE_logError("A pair of links needs to be specified to disable/enable collisions");
562  continue;
563  }
564  const char* reason = c_xml->Attribute("reason");
565 
566  CollisionPair pair{ boost::trim_copy(std::string(link1)), boost::trim_copy(std::string(link2)),
567  reason ? reason : "" };
568  if (!urdf_model.getLink(pair.link1_))
569  {
570  CONSOLE_BRIDGE_logWarn("Link '%s' is not known to URDF. Cannot disable/enable collisons.", link1);
571  continue;
572  }
573  if (!urdf_model.getLink(pair.link2_))
574  {
575  CONSOLE_BRIDGE_logWarn("Link '%s' is not known to URDF. Cannot disable/enable collisons.", link2);
576  continue;
577  }
578  pairs.push_back(pair);
579  }
580 }
581 
582 void srdf::Model::loadPassiveJoints(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
583 {
584  constexpr char JOINT[] = "passive_joint";
585  for (XMLElement* c_xml = robot_xml->FirstChildElement(JOINT); c_xml; c_xml = c_xml->NextSiblingElement(JOINT))
586  {
587  const char* name = c_xml->Attribute("name");
588  if (!name)
589  {
590  CONSOLE_BRIDGE_logError("No name specified for passive joint. Ignoring.");
591  continue;
592  }
593  PassiveJoint pj;
594  pj.name_ = boost::trim_copy(std::string(name));
595 
596  if (!isValidJoint(urdf_model, pj.name_))
597  {
598  CONSOLE_BRIDGE_logError("Joint '%s' marked as passive is not known to the URDF. Ignoring.", name);
599  continue;
600  }
601  passive_joints_.push_back(pj);
602  }
603 }
604 
605 void srdf::Model::loadJointProperties(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
606 {
607  for (XMLElement* prop_xml = robot_xml->FirstChildElement("joint_property"); prop_xml;
608  prop_xml = prop_xml->NextSiblingElement("joint_property"))
609  {
610  const char* jname = prop_xml->Attribute("joint_name");
611  const char* pname = prop_xml->Attribute("property_name");
612  const char* pval = prop_xml->Attribute("value");
613 
614  std::string jname_str = boost::trim_copy(std::string(jname));
615 
616  if (!jname)
617  {
618  CONSOLE_BRIDGE_logError("joint_property is missing a joint name");
619  continue;
620  }
621  if (!pname)
622  {
623  CONSOLE_BRIDGE_logError("Property name for joint '%s' is not specified", jname);
624  continue;
625  }
626  if (!pval)
627  {
628  CONSOLE_BRIDGE_logError("Value is not specified for property '%s' of joint '%s'", pname, jname);
629  continue;
630  }
631 
632  if (!isValidJoint(urdf_model, jname_str))
633  {
634  CONSOLE_BRIDGE_logError("Property defined for a joint '%s' that is not known to the URDF. Ignoring.",
635  jname_str.c_str());
636  continue;
637  }
638  joint_properties_[jname_str][boost::trim_copy(std::string(pname))] = std::string(pval);
639  }
640 }
641 
642 bool srdf::Model::initXml(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
643 {
644  clear();
645  if (!robot_xml || strcmp(robot_xml->Value(), "robot") != 0)
646  {
647  CONSOLE_BRIDGE_logError("Could not find the 'robot' element in the xml file");
648  return false;
649  }
650 
651  // get the robot name
652  const char* name = robot_xml->Attribute("name");
653  if (!name)
654  CONSOLE_BRIDGE_logError("No name given for the robot.");
655  else
656  {
657  name_ = std::string(name);
658  boost::trim(name_);
659  if (name_ != urdf_model.getName())
660  CONSOLE_BRIDGE_logError("Semantic description is not specified for the same robot as the URDF");
661  }
662 
663  loadVirtualJoints(urdf_model, robot_xml);
664  loadGroups(urdf_model, robot_xml);
665  loadGroupStates(urdf_model, robot_xml);
666  loadEndEffectors(urdf_model, robot_xml);
667  loadLinkSphereApproximations(urdf_model, robot_xml);
668  loadCollisionDefaults(urdf_model, robot_xml);
669  loadCollisionPairs(urdf_model, robot_xml, "enable_collisions", enabled_collision_pairs_);
670  loadCollisionPairs(urdf_model, robot_xml, "disable_collisions", disabled_collision_pairs_);
671  loadPassiveJoints(urdf_model, robot_xml);
672  loadJointProperties(urdf_model, robot_xml);
673 
674  return true;
675 }
676 
677 bool srdf::Model::initXml(const urdf::ModelInterface& urdf_model, XMLDocument* xml)
678 {
679  XMLElement* robot_xml = xml ? xml->FirstChildElement("robot") : NULL;
680  return initXml(urdf_model, robot_xml);
681 }
682 
683 bool srdf::Model::initFile(const urdf::ModelInterface& urdf_model, const std::string& filename)
684 {
685  // get the entire file
686  std::string xml_string;
687  std::fstream xml_file(filename.c_str(), std::fstream::in);
688  if (xml_file.is_open())
689  {
690  while (xml_file.good())
691  {
692  std::string line;
693  std::getline(xml_file, line);
694  xml_string += (line + "\n");
695  }
696  xml_file.close();
697  return initString(urdf_model, xml_string);
698  }
699  else
700  {
701  CONSOLE_BRIDGE_logError("Could not open file [%s] for parsing.", filename.c_str());
702  return false;
703  }
704 }
705 
706 bool srdf::Model::initString(const urdf::ModelInterface& urdf_model, const std::string& xmlstring)
707 {
708  XMLDocument xml_doc;
709  if (xml_doc.Parse(xmlstring.c_str()) != XML_SUCCESS)
710  {
711  CONSOLE_BRIDGE_logError("Could not parse the SRDF XML File. %s", xml_doc.ErrorStr());
712  return false;
713  }
714  return initXml(urdf_model, &xml_doc);
715 }
716 
718 {
719  name_ = "";
720  groups_.clear();
721  group_states_.clear();
722  virtual_joints_.clear();
723  end_effectors_.clear();
724  link_sphere_approximations_.clear();
725  no_default_collision_links_.clear();
726  enabled_collision_pairs_.clear();
727  disabled_collision_pairs_.clear();
728  passive_joints_.clear();
729 }
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
model.h
xml_string
def xml_string(rootXml, addHeader=True)
srdf::Model::VirtualJoint::name_
std::string name_
The name of the new joint.
Definition: model.h:180
srdf::Model::Group::chains_
std::vector< std::pair< std::string, std::string > > chains_
Definition: model.h:165
CONSOLE_BRIDGE_logWarn
#define CONSOLE_BRIDGE_logWarn
srdf::Model::loadGroups
void loadGroups(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:119
CONSOLE_BRIDGE_logError
#define CONSOLE_BRIDGE_logError(fmt,...)
srdf::Model::loadGroupStates
void loadGroupStates(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:290
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::PassiveJoint::name_
std::string name_
The name of the new joint.
Definition: model.h:262
srdf::Model::clear
void clear()
Clear the model.
Definition: model.cpp:717
ok
ROSCPP_DECL bool ok()
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::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::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
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
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::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::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::loadLinkSphereApproximations
void loadLinkSphereApproximations(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:434
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::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::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::VirtualJoint
Definition: model.h:177
srdf::Model::Sphere::center_x_
double center_x_
The center of the sphere in the link collision frame.
Definition: model.h:227
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::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::Group
A group consists of a set of joints and the corresponding descendant links. There are multiple ways t...
Definition: model.h:143
srdf::Model::loadVirtualJoints
void loadVirtualJoints(const urdf::ModelInterface &urdf_model, tinyxml2::XMLElement *robot_xml)
Definition: model.cpp:64
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::Group::joints_
std::vector< std::string > joints_
Definition: model.h:153
srdf::Model::EndEffector
Representation of an end effector.
Definition: model.h:193
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


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