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