00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #include "srdf/model.h"
00038 #include <ros/console.h>
00039 #include <boost/lexical_cast.hpp>
00040 #include <boost/algorithm/string/trim.hpp>
00041 #include <algorithm>
00042 #include <fstream>
00043 #include <sstream>
00044 #include <set>
00045 
00046 void srdf::Model::loadVirtualJoints(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
00047 {
00048   for (TiXmlElement* vj_xml = robot_xml->FirstChildElement("virtual_joint"); vj_xml; vj_xml = vj_xml->NextSiblingElement("virtual_joint"))
00049   {
00050     const char *jname = vj_xml->Attribute("name");
00051     const char *child = vj_xml->Attribute("child_link");
00052     const char *parent = vj_xml->Attribute("parent_frame");
00053     const char *type = vj_xml->Attribute("type");
00054     if (!jname)
00055     {
00056       ROS_ERROR("Name of virtual joint is not specified");
00057       continue;
00058     }
00059     if (!child)
00060     {
00061       ROS_ERROR("Child link of virtual joint is not specified");
00062       continue;
00063     }
00064     if (!urdf_model.getLink(boost::trim_copy(std::string(child))))
00065     {
00066       ROS_ERROR("Virtual joint does not attach to a link on the robot (link '%s' is not known)", child);
00067       continue;
00068     }
00069     if (!parent)
00070     {
00071       ROS_ERROR("Parent frame of virtual joint is not specified");
00072       continue;
00073     }
00074     if (!type)
00075     {
00076       ROS_ERROR("Type of virtual joint is not specified");
00077       continue;
00078     }
00079     VirtualJoint vj;
00080     vj.type_ = std::string(type); boost::trim(vj.type_);
00081     std::transform(vj.type_.begin(), vj.type_.end(), vj.type_.begin(), ::tolower);
00082     if (vj.type_ != "planar" && vj.type_ != "floating" && vj.type_ != "fixed")
00083     {
00084       ROS_ERROR("Unknown type of joint: '%s'. Assuming 'fixed' instead. Other known types are 'planar' and 'floating'.", type);
00085       vj.type_ = "fixed";
00086     }
00087     vj.name_ = std::string(jname); boost::trim(vj.name_);        
00088     vj.child_link_ = std::string(child); boost::trim(vj.child_link_);
00089     vj.parent_frame_ = std::string(parent); boost::trim(vj.parent_frame_);
00090     virtual_joints_.push_back(vj);
00091   }
00092 }
00093 
00094 void srdf::Model::loadGroups(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
00095 {
00096   for (TiXmlElement* group_xml = robot_xml->FirstChildElement("group"); group_xml; group_xml = group_xml->NextSiblingElement("group"))
00097   {
00098     const char *gname = group_xml->Attribute("name");
00099     if (!gname)
00100     {
00101       ROS_ERROR("Group name not specified");
00102       continue;
00103     }
00104     Group g;
00105     g.name_ = std::string(gname); boost::trim(g.name_);
00106     
00107     
00108     for (TiXmlElement* link_xml = group_xml->FirstChildElement("link"); link_xml; link_xml = link_xml->NextSiblingElement("link"))
00109     {
00110       const char *lname = link_xml->Attribute("name");
00111       if (!lname)
00112       {
00113         ROS_ERROR("Link name not specified");
00114         continue;
00115       }
00116       std::string lname_str = boost::trim_copy(std::string(lname));
00117       if (!urdf_model.getLink(lname_str))
00118       {
00119         ROS_ERROR("Link '%s' declared as part of group '%s' is not known to the URDF", lname, gname);
00120         continue;
00121       }
00122       g.links_.push_back(lname_str);
00123     }
00124     
00125     
00126     for (TiXmlElement* joint_xml = group_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint"))
00127     {
00128       const char *jname = joint_xml->Attribute("name");
00129       if (!jname)
00130       {
00131         ROS_ERROR("Joint name not specified");
00132         continue;
00133       }
00134       std::string jname_str = boost::trim_copy(std::string(jname));
00135       if (!urdf_model.getJoint(jname_str))
00136       {
00137         bool missing = true;
00138         for (std::size_t k = 0 ; k < virtual_joints_.size() ; ++k)
00139           if (virtual_joints_[k].name_ == jname_str)
00140           {
00141             missing = false;
00142             break;
00143           }
00144         if (missing)
00145         {
00146           ROS_ERROR("Joint '%s' declared as part of group '%s' is not known to the URDF", jname, gname);
00147           continue;
00148         }
00149       }
00150       g.joints_.push_back(jname_str);
00151     }
00152     
00153     
00154     for (TiXmlElement* chain_xml = group_xml->FirstChildElement("chain"); chain_xml; chain_xml = chain_xml->NextSiblingElement("chain"))
00155     {
00156       const char *base = chain_xml->Attribute("base_link");
00157       const char *tip = chain_xml->Attribute("tip_link");
00158       if (!base)
00159       {
00160         ROS_ERROR("Base link name not specified for chain");
00161         continue;
00162       }
00163       if (!tip)
00164       {
00165         ROS_ERROR("Tip link name not specified for chain");
00166         continue;
00167       }
00168       std::string base_str = boost::trim_copy(std::string(base));
00169       std::string tip_str = boost::trim_copy(std::string(tip));
00170       if (!urdf_model.getLink(base_str))
00171       {
00172         ROS_ERROR("Link '%s' declared as part of a chain in group '%s' is not known to the URDF", base, gname);
00173         continue;
00174       }
00175       if (!urdf_model.getLink(tip_str))
00176       {
00177         ROS_ERROR("Link '%s' declared as part of a chain in group '%s' is not known to the URDF", tip, gname);
00178         continue;
00179       }
00180       bool found = false;
00181       boost::shared_ptr<const urdf::Link> l = urdf_model.getLink(tip_str);
00182       std::set<std::string> seen;
00183       while (!found && l)
00184       {
00185         seen.insert(l->name);
00186         if (l->name == base_str)
00187           found = true;
00188         else
00189           l = l->getParent();
00190       }
00191       if (!found)
00192       {
00193         l = urdf_model.getLink(base_str);
00194         while (!found && l)
00195         {
00196           if (seen.find(l->name) != seen.end())
00197             found = true;
00198           else
00199             l = l->getParent();
00200         }
00201       }
00202       if (found)
00203         g.chains_.push_back(std::make_pair(base_str, tip_str));
00204       else
00205         ROS_ERROR("Links '%s' and '%s' do not form a chain. Not included in group '%s'", base, tip, gname);
00206     }
00207     
00208     
00209     for (TiXmlElement* subg_xml = group_xml->FirstChildElement("group"); subg_xml; subg_xml = subg_xml->NextSiblingElement("group"))
00210     {
00211       const char *sub = subg_xml->Attribute("name");
00212       if (!sub)
00213       {
00214         ROS_ERROR("Group name not specified when included as subgroup");
00215         continue;
00216       }
00217       g.subgroups_.push_back(boost::trim_copy(std::string(sub)));
00218     }
00219     if (g.links_.empty() && g.joints_.empty() && g.chains_.empty() && g.subgroups_.empty())
00220       ROS_WARN("Group '%s' is empty.", gname);
00221     groups_.push_back(g);
00222   }
00223   
00224   
00225   std::set<std::string> known_groups;
00226   bool update = true;
00227   while (update)
00228   {
00229     update = false;
00230     for (std::size_t i = 0 ; i < groups_.size() ; ++i)
00231     {
00232       if (known_groups.find(groups_[i].name_) != known_groups.end())
00233         continue;
00234       if (groups_[i].subgroups_.empty())
00235       {
00236         known_groups.insert(groups_[i].name_);
00237         update = true;
00238       }
00239       else
00240       {
00241         bool ok = true;
00242         for (std::size_t j = 0 ; ok && j < groups_[i].subgroups_.size() ; ++j)
00243           if (known_groups.find(groups_[i].subgroups_[j]) == known_groups.end())
00244             ok = false;
00245         if (ok)
00246         {
00247           known_groups.insert(groups_[i].name_);
00248           update = true;
00249         }
00250       }
00251     }
00252   }
00253   
00254   
00255   if (known_groups.size() != groups_.size())
00256   {
00257     std::vector<Group> correct;
00258     for (std::size_t i = 0 ; i < groups_.size() ; ++i)
00259       if (known_groups.find(groups_[i].name_) != known_groups.end())
00260         correct.push_back(groups_[i]);
00261       else
00262         ROS_ERROR("Group '%s' has unsatisfied subgroups", groups_[i].name_.c_str());
00263     groups_.swap(correct);
00264   }
00265 }
00266 
00267 void srdf::Model::loadGroupStates(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
00268 {
00269   for (TiXmlElement* gstate_xml = robot_xml->FirstChildElement("group_state"); gstate_xml; gstate_xml = gstate_xml->NextSiblingElement("group_state"))
00270   {
00271     const char *sname = gstate_xml->Attribute("name");
00272     const char *gname = gstate_xml->Attribute("group");
00273     if (!sname)
00274     {
00275       ROS_ERROR("Name of group state is not specified");
00276       continue;
00277     }
00278     if (!gname)
00279     {
00280       ROS_ERROR("Name of group for state '%s' is not specified", sname);
00281       continue;
00282     }
00283     
00284     GroupState gs;
00285     gs.name_ = boost::trim_copy(std::string(sname));
00286     gs.group_ = boost::trim_copy(std::string(gname));
00287     
00288     bool found = false;
00289     for (std::size_t k = 0 ; k < groups_.size() ; ++k)
00290       if (groups_[k].name_ == gs.group_)
00291       {
00292         found = true;
00293         break;
00294       }
00295     if (!found)
00296     {
00297       ROS_ERROR("Group state '%s' specified for group '%s', but that group is not known", sname, gname);
00298       continue;
00299     }
00300     
00301     
00302     for (TiXmlElement* joint_xml = gstate_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint"))
00303     {
00304       const char *jname = joint_xml->Attribute("name");
00305       const char *jval = joint_xml->Attribute("value");
00306       if (!jname)
00307       {
00308         ROS_ERROR("Joint name not specified in group state '%s'", sname);
00309         continue;
00310       }
00311       if (!jval)
00312       {
00313         ROS_ERROR("Joint name not specified for joint '%s' in group state '%s'", jname, sname);
00314         continue;
00315       }
00316       std::string jname_str = boost::trim_copy(std::string(jname));
00317       if (!urdf_model.getJoint(jname_str))
00318       {
00319         bool missing = true;
00320         for (std::size_t k = 0 ; k < virtual_joints_.size() ; ++k)
00321           if (virtual_joints_[k].name_ == jname_str)
00322           {
00323             missing = false;
00324             break;
00325           }
00326         if (missing)
00327         {
00328           ROS_ERROR("Joint '%s' declared as part of group state '%s' is not known to the URDF", jname, sname);
00329           continue;
00330         }
00331       }
00332       try
00333       {
00334         std::string jval_str = std::string(jval);
00335         std::stringstream ss(jval_str);
00336         while (ss.good() && !ss.eof())
00337         {
00338           std::string val; ss >> val >> std::ws;
00339           gs.joint_values_[jname_str].push_back(boost::lexical_cast<double>(val));
00340         }
00341       }
00342       catch (boost::bad_lexical_cast &e)
00343       {
00344         ROS_ERROR("Unable to parse joint value '%s'", jval);
00345       }
00346       
00347       if (gs.joint_values_.empty())
00348         ROS_ERROR("Unable to parse joint value ('%s') for joint '%s' in group state '%s'", jval, jname, sname);
00349     }
00350     group_states_.push_back(gs);
00351   }
00352 }
00353 
00354 void srdf::Model::loadEndEffectors(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
00355 {
00356   for (TiXmlElement* eef_xml = robot_xml->FirstChildElement("end_effector"); eef_xml; eef_xml = eef_xml->NextSiblingElement("end_effector"))
00357   {
00358     const char *ename = eef_xml->Attribute("name");
00359     const char *gname = eef_xml->Attribute("group");
00360     const char *parent = eef_xml->Attribute("parent_link");
00361     if (!ename)
00362     {
00363       ROS_ERROR("Name of end effector is not specified");
00364       continue;
00365     }
00366     if (!gname)
00367     {
00368       ROS_ERROR("Group not specified for end effector '%s'", ename);
00369       continue;
00370     }
00371     EndEffector e;
00372     e.name_ = std::string(ename); boost::trim(e.name_);
00373     e.component_group_ = std::string(gname); boost::trim(e.component_group_);
00374     bool found = false;
00375     for (std::size_t k = 0 ; k < groups_.size() ; ++k)
00376       if (groups_[k].name_ == e.component_group_)
00377       {
00378         found = true;
00379         break;
00380       }
00381     if (!found)
00382     {
00383       ROS_ERROR("End effector '%s' specified for group '%s', but that group is not known", ename, gname);
00384       continue;
00385     }
00386     if (!parent)
00387     {
00388       ROS_ERROR("Parent link not specified for end effector '%s'", ename);
00389       continue;
00390     }
00391     e.parent_link_ = std::string(parent); boost::trim(e.parent_link_);
00392     if (!urdf_model.getLink(e.parent_link_))
00393     {
00394       ROS_ERROR("Link '%s' specified as parent for end effector '%s' is not known to the URDF", parent, ename);
00395       continue;
00396     }
00397     end_effectors_.push_back(e);
00398   }
00399 }
00400 
00401 void srdf::Model::loadDisabledCollisions(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
00402 {
00403   for (TiXmlElement* c_xml = robot_xml->FirstChildElement("disable_collisions"); c_xml; c_xml = c_xml->NextSiblingElement("disable_collisions"))
00404   {
00405     const char *link1 = c_xml->Attribute("link1");
00406     const char *link2 = c_xml->Attribute("link2");
00407     if (!link1 || !link2)
00408     {
00409       ROS_ERROR("A pair of links needs to be specified to disable collisions");
00410       continue;
00411     }
00412     std::string link1_str = boost::trim_copy(std::string(link1));
00413     std::string link2_str = boost::trim_copy(std::string(link2));
00414     if (!urdf_model.getLink(link1_str))
00415     {
00416       ROS_ERROR("Link '%s' is not known to URDF. Cannot disable collisons.", link1);
00417       continue;
00418     }
00419     if (!urdf_model.getLink(link2_str))
00420     {
00421       ROS_ERROR("Link '%s' is not known to URDF. Cannot disable collisons.", link2);
00422       continue;
00423     }
00424     disabled_collisions_.push_back(std::make_pair(link1_str, link2_str));
00425   }
00426 }
00427 
00428 bool srdf::Model::initXml(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml)
00429 {
00430   clear();
00431   if (!robot_xml || robot_xml->ValueStr() != "robot")
00432   {
00433     ROS_ERROR("Could not find the 'robot' element in the xml file");
00434     return false;
00435   }
00436   
00437   
00438   const char *name = robot_xml->Attribute("name");
00439   if (!name)
00440     ROS_ERROR("No name given for the robot.");
00441   else
00442   {
00443     name_ = std::string(name); boost::trim(name_);
00444     if (name_ != urdf_model.getName())
00445       ROS_ERROR("Semantic description is not specified for the same robot as the URDF");
00446   }
00447   
00448   loadVirtualJoints(urdf_model, robot_xml);
00449   loadGroups(urdf_model, robot_xml);
00450   loadGroupStates(urdf_model, robot_xml);
00451   loadEndEffectors(urdf_model, robot_xml);
00452   loadDisabledCollisions(urdf_model, robot_xml);
00453   
00454   return true;
00455 }
00456 
00457 bool srdf::Model::initXml(const urdf::ModelInterface &urdf_model, TiXmlDocument *xml)
00458 {
00459   TiXmlElement *robot_xml = xml ? xml->FirstChildElement("robot") : NULL;
00460   if (!robot_xml)
00461   {
00462     ROS_ERROR("Could not find the 'robot' element in the xml file");
00463     return false;
00464   }
00465   return initXml(urdf_model, robot_xml);
00466 }
00467 
00468 
00469 bool srdf::Model::initFile(const urdf::ModelInterface &urdf_model, const std::string& filename)
00470 {
00471   
00472   std::string xml_string;
00473   std::fstream xml_file(filename.c_str(), std::fstream::in);
00474   if (xml_file.is_open())
00475   {
00476     while (xml_file.good())
00477     {
00478       std::string line;
00479       std::getline(xml_file, line);
00480       xml_string += (line + "\n");
00481     }
00482     xml_file.close();
00483     return initString(urdf_model, xml_string);
00484   }
00485   else
00486   {
00487     ROS_ERROR("Could not open file [%s] for parsing.", filename.c_str());
00488     return false;
00489   }
00490 }
00491 
00492 bool srdf::Model::initString(const urdf::ModelInterface &urdf_model, const std::string& xmlstring)
00493 {
00494   TiXmlDocument xml_doc;
00495   xml_doc.Parse(xmlstring.c_str());
00496   return initXml(urdf_model, &xml_doc);
00497 }
00498 
00499 
00500 void srdf::Model::clear(void)
00501 {
00502   name_ = "";
00503   groups_.clear();
00504   group_states_.clear();
00505   virtual_joints_.clear();
00506   end_effectors_.clear();
00507   disabled_collisions_.clear();
00508 }