46 #include <urdf_parser/urdf_parser.h> 50 #include <boost/algorithm/string.hpp> 51 #include <boost/scoped_ptr.hpp> 52 #include <boost/thread.hpp> 59 return data.find(
"<COLLADA") != std::string::npos;
65 std::string xml_string;
66 std::fstream xml_file(filename.c_str(), std::fstream::in);
67 if (xml_file.is_open()) {
68 while (xml_file.good() ) {
70 std::getline(xml_file, line);
71 xml_string += (line +
"\n");
76 ROS_ERROR(
"Could not open file [%s] for parsing.",filename.c_str());
89 std::string xml_string;
92 std::string full_param;
94 ROS_ERROR(
"Could not find parameter %s on parameter server", param.c_str());
99 if (!nh.
getParam(full_param, xml_string)){
100 ROS_ERROR(
"Could not read parameter %s on parameter server", full_param.c_str());
109 ROS_ERROR(
"Could not parse the xml document");
113 std::stringstream ss;
122 ROS_ERROR(
"Could not parse the xml element");
126 std::stringstream ss;
134 urdf::ModelInterfaceSharedPtr model;
138 ROS_DEBUG(
"Parsing robot collada xml string");
140 static boost::mutex PARSER_PLUGIN_LOCK;
141 static boost::scoped_ptr<pluginlib::ClassLoader<urdf::URDFParser> > PARSER_PLUGIN_LOADER;
142 boost::mutex::scoped_lock _(PARSER_PLUGIN_LOCK);
146 if (!PARSER_PLUGIN_LOADER)
148 const std::vector<std::string> &classes = PARSER_PLUGIN_LOADER->getDeclaredClasses();
150 for (std::size_t i = 0 ; i < classes.size() ; ++i)
151 if (classes[i].find(
"urdf/ColladaURDFParser") != std::string::npos)
155 model = instance->parse(xml_string);
160 ROS_ERROR_STREAM(
"No URDF parser plugin found for Collada files. Did you install the corresponding package?");
164 ROS_ERROR_STREAM(
"Exception while creating planning plugin loader " << ex.what() <<
". Will not parse Collada file.");
167 ROS_DEBUG(
"Parsing robot urdf xml string");
168 model = parseURDF(xml_string);
173 this->links_ = model->links_;
174 this->joints_ = model->joints_;
175 this->materials_ = model->materials_;
176 this->name_ = model->name_;
177 this->root_link_ = model->root_link_;
URDF_EXPORT bool initFile(const std::string &filename)
Load Model given a filename.
static bool IsColladaData(const std::string &data)
URDF_EXPORT bool initString(const std::string &xmlstring)
Load Model from a XML-string.
URDF_EXPORT bool initXml(TiXmlElement *xml)
Load Model from TiXMLElement.
URDF_EXPORT bool initParamWithNodeHandle(const std::string ¶m, const ros::NodeHandle &nh=ros::NodeHandle())
Load Model given the name of parameter on parameter server using provided nodehandle.
bool searchParam(const std::string &key, std::string &result) const
URDF_EXPORT bool initParam(const std::string ¶m)
Load Model given the name of a parameter on the parameter server.
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)