38 #include <console_bridge/console.h>
39 #include <boost/algorithm/string/trim.hpp>
46 using namespace tinyxml2;
50 if (urdf_model.getJoint(name))
66 for (XMLElement* vj_xml = robot_xml->FirstChildElement(
"virtual_joint"); vj_xml;
67 vj_xml = vj_xml->NextSiblingElement(
"virtual_joint"))
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");
83 if (!urdf_model.getLink(boost::trim_copy(std::string(child))))
85 CONSOLE_BRIDGE_logError(
"Virtual joint does not attach to a link on the robot (link '%s' is not known)", child);
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")
104 CONSOLE_BRIDGE_logError(
"Unknown type of joint: '%s'. Assuming 'fixed' instead. Other known types are 'planar' "
109 vj.
name_ = std::string(jname);
110 boost::trim(vj.
name_);
115 virtual_joints_.push_back(vj);
121 for (XMLElement* group_xml = robot_xml->FirstChildElement(
"group"); group_xml;
122 group_xml = group_xml->NextSiblingElement(
"group"))
124 const char* gname = group_xml->Attribute(
"name");
131 g.
name_ = std::string(gname);
132 boost::trim(g.
name_);
135 for (XMLElement* link_xml = group_xml->FirstChildElement(
"link"); link_xml;
136 link_xml = link_xml->NextSiblingElement(
"link"))
138 const char* lname = link_xml->Attribute(
"name");
144 std::string lname_str = boost::trim_copy(std::string(lname));
145 if (!urdf_model.getLink(lname_str))
150 g.
links_.push_back(lname_str);
154 for (XMLElement* joint_xml = group_xml->FirstChildElement(
"joint"); joint_xml;
155 joint_xml = joint_xml->NextSiblingElement(
"joint"))
157 const char* jname = joint_xml->Attribute(
"name");
163 std::string jname_str = boost::trim_copy(std::string(jname));
164 if (!isValidJoint(urdf_model, jname_str))
169 g.
joints_.push_back(jname_str);
173 for (XMLElement* chain_xml = group_xml->FirstChildElement(
"chain"); chain_xml;
174 chain_xml = chain_xml->NextSiblingElement(
"chain"))
176 const char* base = chain_xml->Attribute(
"base_link");
177 const char* tip = chain_xml->Attribute(
"tip_link");
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))
196 if (!urdf_model.getLink(tip_str))
203 urdf::LinkConstSharedPtr l = urdf_model.getLink(tip_str);
204 std::set<std::string> seen;
207 seen.insert(l->name);
208 if (l->name == base_str)
215 l = urdf_model.getLink(base_str);
218 if (seen.find(l->name) != seen.end())
225 g.
chains_.push_back(std::make_pair(base_str, tip_str));
227 CONSOLE_BRIDGE_logError(
"Links '%s' and '%s' do not form a chain. Not included in group '%s'", base, tip, gname);
231 for (XMLElement* subg_xml = group_xml->FirstChildElement(
"group"); subg_xml;
232 subg_xml = subg_xml->NextSiblingElement(
"group"))
234 const char* sub = subg_xml->Attribute(
"name");
240 g.
subgroups_.push_back(boost::trim_copy(std::string(sub)));
244 groups_.push_back(g);
248 std::set<std::string> known_groups;
253 for (std::size_t i = 0; i < groups_.size(); ++i)
255 if (known_groups.find(groups_[i].name_) != known_groups.end())
257 if (groups_[i].subgroups_.empty())
259 known_groups.insert(groups_[i].name_);
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())
270 known_groups.insert(groups_[i].name_);
278 if (known_groups.size() != groups_.size())
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]);
286 groups_.swap(correct);
292 for (XMLElement* gstate_xml = robot_xml->FirstChildElement(
"group_state"); gstate_xml;
293 gstate_xml = gstate_xml->NextSiblingElement(
"group_state"))
295 const char* sname = gstate_xml->Attribute(
"name");
296 const char* gname = gstate_xml->Attribute(
"group");
309 gs.
name_ = boost::trim_copy(std::string(sname));
310 gs.
group_ = boost::trim_copy(std::string(gname));
313 for (std::size_t k = 0; k < groups_.size(); ++k)
314 if (groups_[k].name_ == gs.
group_)
321 CONSOLE_BRIDGE_logError(
"Group state '%s' specified for group '%s', but that group is not known", sname, gname);
326 for (XMLElement* joint_xml = gstate_xml->FirstChildElement(
"joint"); joint_xml;
327 joint_xml = joint_xml->NextSiblingElement(
"joint"))
329 const char* jname = joint_xml->Attribute(
"name");
330 const char* jval = joint_xml->Attribute(
"value");
341 std::string jname_str = boost::trim_copy(std::string(jname));
342 if (!isValidJoint(urdf_model, jname_str))
350 std::string jval_str = std::string(jval);
351 std::istringstream ss(jval_str);
352 while (ss.good() && !ss.eof())
355 ss >> val >> std::ws;
359 catch (
const std::invalid_argument& e)
363 catch (
const std::out_of_range& e)
372 group_states_.push_back(gs);
378 for (XMLElement* eef_xml = robot_xml->FirstChildElement(
"end_effector"); eef_xml;
379 eef_xml = eef_xml->NextSiblingElement(
"end_effector"))
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");
396 e.
name_ = std::string(ename);
397 boost::trim(e.
name_);
401 for (std::size_t k = 0; k < groups_.size(); ++k)
409 CONSOLE_BRIDGE_logError(
"End effector '%s' specified for group '%s', but that group is not known", ename, gname);
421 CONSOLE_BRIDGE_logError(
"Link '%s' specified as parent for end effector '%s' is not known to the URDF", parent,
430 end_effectors_.push_back(e);
436 for (XMLElement* cslink_xml = robot_xml->FirstChildElement(
"link_sphere_approximation"); cslink_xml;
437 cslink_xml = cslink_xml->NextSiblingElement(
"link_sphere_approximation"))
439 int non_0_radius_sphere_cnt = 0;
440 const char* link_name = cslink_xml->Attribute(
"link");
448 link_spheres.
link_ = boost::trim_copy(std::string(link_name));
449 if (!urdf_model.getLink(link_spheres.
link_))
457 for (XMLElement* sphere_xml = cslink_xml->FirstChildElement(
"sphere"); sphere_xml;
458 sphere_xml = sphere_xml->NextSiblingElement(
"sphere"), cnt++)
460 const char* s_center = sphere_xml->Attribute(
"center");
461 const char* s_r = sphere_xml->Attribute(
"radius");
462 if (!s_center || !s_r)
472 std::stringstream center(s_center);
473 center.exceptions(std::stringstream::failbit | std::stringstream::badbit);
475 sphere.
radius_ = std::stod(s_r);
477 catch (std::stringstream::failure& e)
483 catch (
const std::invalid_argument& e)
489 catch (
const std::out_of_range& e)
508 if (sphere.
radius_ > std::numeric_limits<double>::epsilon())
510 if (non_0_radius_sphere_cnt == 0)
512 link_spheres.
spheres_.push_back(sphere);
513 non_0_radius_sphere_cnt++;
515 else if (non_0_radius_sphere_cnt == 0)
522 link_spheres.
spheres_.push_back(sphere);
527 link_sphere_approximations_.push_back(link_spheres);
533 for (XMLElement* xml = robot_xml->FirstChildElement(
"disable_default_collisions"); xml;
534 xml = xml->NextSiblingElement(
"disable_default_collisions"))
536 const char* link_ = xml->Attribute(
"link");
542 std::string link = boost::trim_copy(std::string(link_));
543 if (!urdf_model.getLink(link))
548 no_default_collision_links_.push_back(link);
553 const char* tag_name, std::vector<CollisionPair>& pairs)
555 for (XMLElement* c_xml = robot_xml->FirstChildElement(tag_name); c_xml; c_xml = c_xml->NextSiblingElement(tag_name))
557 const char* link1 = c_xml->Attribute(
"link1");
558 const char* link2 = c_xml->Attribute(
"link2");
559 if (!link1 || !link2)
564 const char* reason = c_xml->Attribute(
"reason");
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_))
573 if (!urdf_model.getLink(pair.link2_))
578 pairs.push_back(pair);
584 constexpr
char JOINT[] =
"passive_joint";
585 for (XMLElement* c_xml = robot_xml->FirstChildElement(JOINT); c_xml; c_xml = c_xml->NextSiblingElement(JOINT))
587 const char* name = c_xml->Attribute(
"name");
594 pj.
name_ = boost::trim_copy(std::string(name));
596 if (!isValidJoint(urdf_model, pj.
name_))
601 passive_joints_.push_back(pj);
607 for (XMLElement* prop_xml = robot_xml->FirstChildElement(
"joint_property"); prop_xml;
608 prop_xml = prop_xml->NextSiblingElement(
"joint_property"))
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");
614 std::string jname_str = boost::trim_copy(std::string(jname));
632 if (!isValidJoint(urdf_model, jname_str))
638 joint_properties_[jname_str][boost::trim_copy(std::string(pname))] = std::string(pval);
645 if (!robot_xml || strcmp(robot_xml->Value(),
"robot") != 0)
652 const char* name = robot_xml->Attribute(
"name");
657 name_ = std::string(name);
659 if (name_ != urdf_model.getName())
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);
679 XMLElement* robot_xml = xml ? xml->FirstChildElement(
"robot") : NULL;
680 return initXml(urdf_model, robot_xml);
687 std::fstream xml_file(filename.c_str(), std::fstream::in);
688 if (xml_file.is_open())
690 while (xml_file.good())
693 std::getline(xml_file, line);
709 if (xml_doc.Parse(xmlstring.c_str()) != XML_SUCCESS)
714 return initXml(urdf_model, &xml_doc);
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();