38 #include <console_bridge/console.h> 39 #include <boost/algorithm/string/trim.hpp> 48 for (TiXmlElement* vj_xml = robot_xml->FirstChildElement(
"virtual_joint"); vj_xml;
49 vj_xml = vj_xml->NextSiblingElement(
"virtual_joint"))
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");
65 if (!urdf_model.getLink(boost::trim_copy(std::string(child))))
67 CONSOLE_BRIDGE_logError(
"Virtual joint does not attach to a link on the robot (link '%s' is not known)", child);
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")
86 CONSOLE_BRIDGE_logError(
"Unknown type of joint: '%s'. Assuming 'fixed' instead. Other known types are 'planar' " 91 vj.
name_ = std::string(jname);
92 boost::trim(vj.
name_);
103 for (TiXmlElement* group_xml = robot_xml->FirstChildElement(
"group"); group_xml;
104 group_xml = group_xml->NextSiblingElement(
"group"))
106 const char* gname = group_xml->Attribute(
"name");
113 g.
name_ = std::string(gname);
114 boost::trim(g.
name_);
117 for (TiXmlElement* link_xml = group_xml->FirstChildElement(
"link"); link_xml;
118 link_xml = link_xml->NextSiblingElement(
"link"))
120 const char* lname = link_xml->Attribute(
"name");
126 std::string lname_str = boost::trim_copy(std::string(lname));
127 if (!urdf_model.getLink(lname_str))
132 g.
links_.push_back(lname_str);
136 for (TiXmlElement* joint_xml = group_xml->FirstChildElement(
"joint"); joint_xml;
137 joint_xml = joint_xml->NextSiblingElement(
"joint"))
139 const char* jname = joint_xml->Attribute(
"name");
145 std::string jname_str = boost::trim_copy(std::string(jname));
146 if (!urdf_model.getJoint(jname_str))
161 g.
joints_.push_back(jname_str);
165 for (TiXmlElement* chain_xml = group_xml->FirstChildElement(
"chain"); chain_xml;
166 chain_xml = chain_xml->NextSiblingElement(
"chain"))
168 const char* base = chain_xml->Attribute(
"base_link");
169 const char* tip = chain_xml->Attribute(
"tip_link");
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))
188 if (!urdf_model.getLink(tip_str))
195 urdf::LinkConstSharedPtr l = urdf_model.getLink(tip_str);
196 std::set<std::string> seen;
199 seen.insert(l->name);
200 if (l->name == base_str)
207 l = urdf_model.getLink(base_str);
210 if (seen.find(l->name) != seen.end())
217 g.
chains_.push_back(std::make_pair(base_str, tip_str));
224 for (TiXmlElement* subg_xml = group_xml->FirstChildElement(
"group"); subg_xml;
225 subg_xml = subg_xml->NextSiblingElement(
"group"))
227 const char* sub = subg_xml->Attribute(
"name");
233 g.
subgroups_.push_back(boost::trim_copy(std::string(sub)));
241 std::set<std::string> known_groups;
246 for (std::size_t i = 0; i <
groups_.size(); ++i)
248 if (known_groups.find(
groups_[i].name_) != known_groups.end())
250 if (
groups_[i].subgroups_.empty())
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())
271 if (known_groups.size() !=
groups_.size())
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())
285 for (TiXmlElement* gstate_xml = robot_xml->FirstChildElement(
"group_state"); gstate_xml;
286 gstate_xml = gstate_xml->NextSiblingElement(
"group_state"))
288 const char* sname = gstate_xml->Attribute(
"name");
289 const char* gname = gstate_xml->Attribute(
"group");
302 gs.
name_ = boost::trim_copy(std::string(sname));
303 gs.
group_ = boost::trim_copy(std::string(gname));
306 for (std::size_t k = 0; k <
groups_.size(); ++k)
314 CONSOLE_BRIDGE_logError(
"Group state '%s' specified for group '%s', but that group is not known", sname, gname);
319 for (TiXmlElement* joint_xml = gstate_xml->FirstChildElement(
"joint"); joint_xml;
320 joint_xml = joint_xml->NextSiblingElement(
"joint"))
322 const char* jname = joint_xml->Attribute(
"name");
323 const char* jval = joint_xml->Attribute(
"value");
334 std::string jname_str = boost::trim_copy(std::string(jname));
335 if (!urdf_model.getJoint(jname_str))
353 std::string jval_str = std::string(jval);
354 std::istringstream ss(jval_str);
355 while (ss.good() && !ss.eof())
358 ss >> val >> std::ws;
362 catch (
const std::invalid_argument& e)
366 catch (
const std::out_of_range& e)
381 for (TiXmlElement* eef_xml = robot_xml->FirstChildElement(
"end_effector"); eef_xml;
382 eef_xml = eef_xml->NextSiblingElement(
"end_effector"))
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");
399 e.
name_ = std::string(ename);
400 boost::trim(e.
name_);
404 for (std::size_t k = 0; k <
groups_.size(); ++k)
412 CONSOLE_BRIDGE_logError(
"End effector '%s' specified for group '%s', but that group is not known", ename, gname);
424 CONSOLE_BRIDGE_logError(
"Link '%s' specified as parent for end effector '%s' is not known to the URDF", parent,
439 for (TiXmlElement* cslink_xml = robot_xml->FirstChildElement(
"link_sphere_approximation"); cslink_xml;
440 cslink_xml = cslink_xml->NextSiblingElement(
"link_sphere_approximation"))
442 int non_0_radius_sphere_cnt = 0;
443 const char* link_name = cslink_xml->Attribute(
"link");
451 link_spheres.
link_ = boost::trim_copy(std::string(link_name));
452 if (!urdf_model.getLink(link_spheres.
link_))
460 for (TiXmlElement* sphere_xml = cslink_xml->FirstChildElement(
"sphere"); sphere_xml;
461 sphere_xml = sphere_xml->NextSiblingElement(
"sphere"), cnt++)
463 const char* s_center = sphere_xml->Attribute(
"center");
464 const char* s_r = sphere_xml->Attribute(
"radius");
465 if (!s_center || !s_r)
475 std::stringstream center(s_center);
476 center.exceptions(std::stringstream::failbit | std::stringstream::badbit);
478 sphere.
radius_ = std::stod(s_r);
480 catch (std::stringstream::failure& e)
486 catch (
const std::invalid_argument& e)
492 catch (
const std::out_of_range& e)
511 if (sphere.
radius_ > std::numeric_limits<double>::epsilon())
513 if (non_0_radius_sphere_cnt == 0)
515 link_spheres.
spheres_.push_back(sphere);
516 non_0_radius_sphere_cnt++;
518 else if (non_0_radius_sphere_cnt == 0)
525 link_spheres.
spheres_.push_back(sphere);
536 for (TiXmlElement* c_xml = robot_xml->FirstChildElement(
"disable_collisions"); c_xml;
537 c_xml = c_xml->NextSiblingElement(
"disable_collisions"))
539 const char* link1 = c_xml->Attribute(
"link1");
540 const char* link2 = c_xml->Attribute(
"link2");
541 if (!link1 || !link2)
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_))
554 if (!urdf_model.getLink(dc.
link2_))
559 const char* reason = c_xml->Attribute(
"reason");
561 dc.
reason_ = std::string(reason);
568 for (TiXmlElement* c_xml = robot_xml->FirstChildElement(
"passive_joint"); c_xml;
569 c_xml = c_xml->NextSiblingElement(
"passive_joint"))
571 const char* name = c_xml->Attribute(
"name");
578 pj.
name_ = boost::trim_copy(std::string(name));
586 if (!vjoint && !urdf_model.getJoint(pj.
name_))
598 if (!robot_xml || robot_xml->ValueStr() !=
"robot")
605 const char* name = robot_xml->Attribute(
"name");
610 name_ = std::string(name);
612 if (
name_ != urdf_model.getName())
629 TiXmlElement* robot_xml = xml ? xml->FirstChildElement(
"robot") : NULL;
635 return initXml(urdf_model, robot_xml);
642 std::fstream xml_file(filename.c_str(), std::fstream::in);
643 if (xml_file.is_open())
645 while (xml_file.good())
648 std::getline(xml_file, line);
649 xml_string += (line +
"\n");
663 TiXmlDocument xml_doc;
664 xml_doc.Parse(xmlstring.c_str());
670 return initXml(urdf_model, &xml_doc);
687 std::vector<std::pair<std::string, std::string> > result;
void loadVirtualJoints(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::vector< std::string > subgroups_
std::vector< VirtualJoint > virtual_joints_
The definition of a disabled collision between two links.
std::string type_
The type of this new joint. This can be "fixed" (0 DOF), "planar" (3 DOF: x,y,yaw) or "floating" (6DO...
std::string link1_
The name of the first link (as in URDF) of the disabled collision.
std::string link2_
The name of the second link (as in URDF) of the disabled collision.
std::map< std::string, std::vector< double > > joint_values_
std::vector< std::pair< std::string, std::string > > chains_
bool initFile(const urdf::ModelInterface &urdf_model, const std::string &filename)
Load Model given a filename.
std::vector< EndEffector > end_effectors_
void loadPassiveJoints(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::string name_
The name of the end effector.
A named state for a particular group.
std::vector< GroupState > group_states_
The definition of a list of spheres for a link.
std::vector< std::pair< std::string, std::string > > getDisabledCollisions() const
double center_x_
The center of the sphere in the link collision frame.
void loadDisabledCollisions(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::string name_
The name of the state.
std::string parent_link_
The name of the link this end effector connects to.
#define CONSOLE_BRIDGE_logWarn
std::vector< Group > groups_
void loadGroupStates(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::string reason_
The reason why the collision check was disabled.
bool initString(const urdf::ModelInterface &urdf_model, const std::string &xmlstring)
Load Model from a XML-string.
std::string parent_frame_
The transform applied by this joint to the robot model brings that model to a particular frame...
The definition of a sphere.
double radius_
The radius of the sphere.
Representation of an end effector.
std::string link_
The name of the link (as in URDF).
std::string name_
The name of the group.
std::vector< DisabledCollision > disabled_collisions_
def xml_string(rootXml, addHeader=True)
A group consists of a set of joints and the corresponding descendant links. There are multiple ways t...
void loadLinkSphereApproximations(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::vector< std::string > links_
void loadEndEffectors(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::string child_link_
The link this joint applies to.
std::vector< Sphere > spheres_
The spheres for the link.
std::vector< std::string > joints_
bool initXml(const urdf::ModelInterface &urdf_model, TiXmlElement *xml)
Load Model from TiXMLElement.
std::vector< PassiveJoint > passive_joints_
std::string name_
The name of the new joint.
std::string component_group_
The name of the group that includes the joints & links this end effector consists of...
std::string name_
The name of the new joint.
void clear()
Clear the model.
void loadGroups(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
std::string parent_group_
std::string group_
The name of the group this state is specified for.
std::vector< LinkSpheres > link_sphere_approximations_