38 #include <console_bridge/console.h> 39 #include <boost/lexical_cast.hpp> 40 #include <boost/algorithm/string/trim.hpp> 49 for (TiXmlElement* vj_xml = robot_xml->FirstChildElement(
"virtual_joint"); vj_xml; 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); boost::trim(vj.
type_);
82 std::transform(vj.
type_.begin(), vj.
type_.end(), vj.
type_.begin(), ::tolower);
83 if (vj.
type_ !=
"planar" && vj.
type_ !=
"floating" && vj.
type_ !=
"fixed")
85 CONSOLE_BRIDGE_logError(
"Unknown type of joint: '%s'. Assuming 'fixed' instead. Other known types are 'planar' and 'floating'.", type);
88 vj.
name_ = std::string(jname); boost::trim(vj.
name_);
97 for (TiXmlElement* group_xml = robot_xml->FirstChildElement(
"group"); group_xml; group_xml = group_xml->NextSiblingElement(
"group"))
99 const char *gname = group_xml->Attribute(
"name");
106 g.
name_ = std::string(gname); boost::trim(g.
name_);
109 for (TiXmlElement* link_xml = group_xml->FirstChildElement(
"link"); link_xml; link_xml = link_xml->NextSiblingElement(
"link"))
111 const char *lname = link_xml->Attribute(
"name");
117 std::string lname_str = boost::trim_copy(std::string(lname));
118 if (!urdf_model.getLink(lname_str))
123 g.
links_.push_back(lname_str);
127 for (TiXmlElement* joint_xml = group_xml->FirstChildElement(
"joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement(
"joint"))
129 const char *jname = joint_xml->Attribute(
"name");
135 std::string jname_str = boost::trim_copy(std::string(jname));
136 if (!urdf_model.getJoint(jname_str))
151 g.
joints_.push_back(jname_str);
155 for (TiXmlElement* chain_xml = group_xml->FirstChildElement(
"chain"); chain_xml; chain_xml = chain_xml->NextSiblingElement(
"chain"))
157 const char *base = chain_xml->Attribute(
"base_link");
158 const char *tip = chain_xml->Attribute(
"tip_link");
169 std::string base_str = boost::trim_copy(std::string(base));
170 std::string tip_str = boost::trim_copy(std::string(tip));
171 if (!urdf_model.getLink(base_str))
173 CONSOLE_BRIDGE_logError(
"Link '%s' declared as part of a chain in group '%s' is not known to the URDF", base, gname);
176 if (!urdf_model.getLink(tip_str))
178 CONSOLE_BRIDGE_logError(
"Link '%s' declared as part of a chain in group '%s' is not known to the URDF", tip, gname);
182 urdf::LinkConstSharedPtr l = urdf_model.getLink(tip_str);
183 std::set<std::string> seen;
186 seen.insert(l->name);
187 if (l->name == base_str)
194 l = urdf_model.getLink(base_str);
197 if (seen.find(l->name) != seen.end())
204 g.
chains_.push_back(std::make_pair(base_str, tip_str));
206 CONSOLE_BRIDGE_logError(
"Links '%s' and '%s' do not form a chain. Not included in group '%s'", base, tip, gname);
210 for (TiXmlElement* subg_xml = group_xml->FirstChildElement(
"group"); subg_xml; subg_xml = subg_xml->NextSiblingElement(
"group"))
212 const char *sub = subg_xml->Attribute(
"name");
218 g.
subgroups_.push_back(boost::trim_copy(std::string(sub)));
226 std::set<std::string> known_groups;
231 for (std::size_t i = 0 ; i <
groups_.size() ; ++i)
233 if (known_groups.find(
groups_[i].name_) != known_groups.end())
235 if (
groups_[i].subgroups_.empty())
243 for (std::size_t j = 0 ; ok && j <
groups_[i].subgroups_.size() ; ++j)
244 if (known_groups.find(
groups_[i].subgroups_[j]) == known_groups.end())
256 if (known_groups.size() !=
groups_.size())
258 std::vector<Group> correct;
259 for (std::size_t i = 0 ; i <
groups_.size() ; ++i)
260 if (known_groups.find(
groups_[i].name_) != known_groups.end())
270 for (TiXmlElement* gstate_xml = robot_xml->FirstChildElement(
"group_state"); gstate_xml; gstate_xml = gstate_xml->NextSiblingElement(
"group_state"))
272 const char *sname = gstate_xml->Attribute(
"name");
273 const char *gname = gstate_xml->Attribute(
"group");
286 gs.
name_ = boost::trim_copy(std::string(sname));
287 gs.
group_ = boost::trim_copy(std::string(gname));
290 for (std::size_t k = 0 ; k <
groups_.size() ; ++k)
298 CONSOLE_BRIDGE_logError(
"Group state '%s' specified for group '%s', but that group is not known", sname, gname);
303 for (TiXmlElement* joint_xml = gstate_xml->FirstChildElement(
"joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement(
"joint"))
305 const char *jname = joint_xml->Attribute(
"name");
306 const char *jval = joint_xml->Attribute(
"value");
317 std::string jname_str = boost::trim_copy(std::string(jname));
318 if (!urdf_model.getJoint(jname_str))
329 CONSOLE_BRIDGE_logError(
"Joint '%s' declared as part of group state '%s' is not known to the URDF", jname, sname);
335 std::string jval_str = std::string(jval);
336 std::stringstream ss(jval_str);
337 while (ss.good() && !ss.eof())
339 std::string val; ss >> val >> std::ws;
340 gs.
joint_values_[jname_str].push_back(boost::lexical_cast<double>(val));
343 catch (boost::bad_lexical_cast &e)
349 CONSOLE_BRIDGE_logError(
"Unable to parse joint value ('%s') for joint '%s' in group state '%s'", jval, jname, sname);
357 for (TiXmlElement* eef_xml = robot_xml->FirstChildElement(
"end_effector"); eef_xml; eef_xml = eef_xml->NextSiblingElement(
"end_effector"))
359 const char *ename = eef_xml->Attribute(
"name");
360 const char *gname = eef_xml->Attribute(
"group");
361 const char *parent = eef_xml->Attribute(
"parent_link");
362 const char *parent_group = eef_xml->Attribute(
"parent_group");
374 e.
name_ = std::string(ename); boost::trim(e.
name_);
377 for (std::size_t k = 0 ; k <
groups_.size() ; ++k)
385 CONSOLE_BRIDGE_logError(
"End effector '%s' specified for group '%s', but that group is not known", ename, gname);
396 CONSOLE_BRIDGE_logError(
"Link '%s' specified as parent for end effector '%s' is not known to the URDF", parent, ename);
409 for (TiXmlElement* cslink_xml = robot_xml->FirstChildElement(
"link_sphere_approximation"); cslink_xml; cslink_xml = cslink_xml->NextSiblingElement(
"link_sphere_approximation"))
411 int non_0_radius_sphere_cnt = 0;
412 const char *link_name = cslink_xml->Attribute(
"link");
420 link_spheres.
link_ = boost::trim_copy(std::string(link_name));
421 if (!urdf_model.getLink(link_spheres.
link_))
430 for (TiXmlElement* sphere_xml = cslink_xml->FirstChildElement(
"sphere"); sphere_xml; sphere_xml = sphere_xml->NextSiblingElement(
"sphere"), cnt++)
432 const char *s_center = sphere_xml->Attribute(
"center");
433 const char *s_r = sphere_xml->Attribute(
"radius");
434 if (!s_center || !s_r)
436 CONSOLE_BRIDGE_logError(
"Link collision sphere %d for link '%s' does not have both center and radius.", cnt, link_name);
443 std::stringstream center(s_center);
444 center.exceptions(std::stringstream::failbit | std::stringstream::badbit);
446 sphere.
radius_ = boost::lexical_cast<
double>(s_r);
448 catch (std::stringstream::failure &e)
450 CONSOLE_BRIDGE_logError(
"Link collision sphere %d for link '%s' has bad center attribute value.", cnt, link_name);
453 catch (boost::bad_lexical_cast &e)
455 CONSOLE_BRIDGE_logError(
"Link collision sphere %d for link '%s' has bad radius attribute value.", cnt, link_name);
471 if (sphere.
radius_ > std::numeric_limits<double>::epsilon())
473 if (non_0_radius_sphere_cnt == 0)
475 link_spheres.
spheres_.push_back(sphere);
476 non_0_radius_sphere_cnt++;
478 else if (non_0_radius_sphere_cnt == 0)
485 link_spheres.
spheres_.push_back(sphere);
496 for (TiXmlElement* c_xml = robot_xml->FirstChildElement(
"disable_collisions"); c_xml; c_xml = c_xml->NextSiblingElement(
"disable_collisions"))
498 const char *link1 = c_xml->Attribute(
"link1");
499 const char *link2 = c_xml->Attribute(
"link2");
500 if (!link1 || !link2)
506 dc.
link1_ = boost::trim_copy(std::string(link1));
507 dc.
link2_ = boost::trim_copy(std::string(link2));
508 if (!urdf_model.getLink(dc.
link1_))
513 if (!urdf_model.getLink(dc.
link2_))
518 const char *reason = c_xml->Attribute(
"reason");
520 dc.
reason_ = std::string(reason);
527 for (TiXmlElement* c_xml = robot_xml->FirstChildElement(
"passive_joint"); c_xml; c_xml = c_xml->NextSiblingElement(
"passive_joint"))
529 const char *name = c_xml->Attribute(
"name");
536 pj.
name_ = boost::trim_copy(std::string(name));
544 if (!vjoint && !urdf_model.getJoint(pj.
name_))
556 if (!robot_xml || robot_xml->ValueStr() !=
"robot")
563 const char *name = robot_xml->Attribute(
"name");
568 name_ = std::string(name); boost::trim(
name_);
569 if (
name_ != urdf_model.getName())
586 TiXmlElement *robot_xml = xml ? xml->FirstChildElement(
"robot") : NULL;
592 return initXml(urdf_model, robot_xml);
600 std::fstream xml_file(filename.c_str(), std::fstream::in);
601 if (xml_file.is_open())
603 while (xml_file.good())
606 std::getline(xml_file, line);
607 xml_string += (line +
"\n");
621 TiXmlDocument xml_doc;
622 xml_doc.Parse(xmlstring.c_str());
623 return initXml(urdf_model, &xml_doc);
639 std::vector<std::pair<std::string, std::string> > srdf::Model::getDisabledCollisions()
const 641 std::vector<std::pair<std::string, std::string> > result;
#define CONSOLE_BRIDGE_logWarn(fmt,...)
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_
The values of joints for this state. Each joint can have a value. We use a vector for the 'value' to ...
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.
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.
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)
#define CONSOLE_BRIDGE_logError(fmt,...)
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_